call_cca.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2012, 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 
00035 /* Author: Ioan Sucan */
00036 
00037 #include <ros/ros.h>
00038 #include <moveit_msgs/ConstructConstraintApproximation.h>
00039 
00040 static const std::string ROBOT_DESCRIPTION="robot_description";
00041 static const std::string CONSTRUCT_CONSTRAINT_APPROXIMATION_SERVICE_NAME="ompl_planning/construct_constraint_approximation";
00042 
00043 moveit_msgs::ConstructConstraintApproximation::Request getDualArmConstraint()
00044 {
00045   moveit_msgs::Constraints c;
00046   moveit_msgs::PositionConstraint pcm2;
00047   pcm2.link_name = "r_wrist_roll_link";
00048   pcm2.header.frame_id = "l_wrist_roll_link";
00049 
00050   pcm2.target_point_offset.x = 0.7;
00051   pcm2.target_point_offset.y = 0;
00052   pcm2.target_point_offset.z = 0;
00053   pcm2.constraint_region.primitives.resize(1);
00054   pcm2.constraint_region.primitives[0].type = shape_msgs::SolidPrimitive::BOX;
00055   pcm2.constraint_region.primitives[0].dimensions.x = 0.01;
00056   pcm2.constraint_region.primitives[0].dimensions.y = 0.01;
00057   pcm2.constraint_region.primitives[0].dimensions.z = 0.01;
00058 
00059   pcm2.constraint_region.primitive_poses.resize(1);
00060   pcm2.constraint_region.primitive_poses[0].position.x = 0.0;
00061   pcm2.constraint_region.primitive_poses[0].position.y = 0.0;
00062   pcm2.constraint_region.primitive_poses[0].position.z = 0.0;
00063   pcm2.constraint_region.primitive_poses[0].orientation.x = 0.0;
00064   pcm2.constraint_region.primitive_poses[0].orientation.y = 0.0;
00065   pcm2.constraint_region.primitive_poses[0].orientation.z = 0.0;
00066   pcm2.constraint_region.primitive_poses[0].orientation.w = 1.0;
00067   pcm2.weight = 1.0;
00068   c.position_constraints.push_back(pcm2);
00069 
00070   moveit_msgs::OrientationConstraint ocm;
00071   ocm.link_name = "l_wrist_roll_link";
00072   ocm.header.frame_id = "odom_combined";
00073   ocm.orientation.x = 0.5;
00074   ocm.orientation.y = 0.5;
00075   ocm.orientation.z = 0.5;
00076   ocm.orientation.w = 0.5;
00077   ocm.absolute_x_axis_tolerance = 0.01;
00078   ocm.absolute_y_axis_tolerance = M_PI;
00079   ocm.absolute_z_axis_tolerance = 0.01;
00080   ocm.weight = 1.0;
00081   c.orientation_constraints.push_back(ocm);
00082 
00083   ocm.link_name = "r_wrist_roll_link";
00084   ocm.header.frame_id = "l_wrist_roll_link";
00085   ocm.orientation.x = 0.0;
00086   ocm.orientation.y = 0.0;
00087   ocm.orientation.z = 1.0;
00088   ocm.orientation.w = 0.0;
00089   ocm.absolute_x_axis_tolerance = 0.01;
00090   ocm.absolute_y_axis_tolerance = 0.01;
00091   ocm.absolute_z_axis_tolerance = 0.01;
00092   ocm.weight = 1.0;
00093   c.orientation_constraints.push_back(ocm);
00094 
00095   moveit_msgs::ConstructConstraintApproximation::Request cca;
00096   cca.constraint = c;
00097   cca.group = "arms";
00098   cca.state_space_parameterization = "PoseModel";
00099   cca.samples = 1000;
00100   cca.edges_per_sample = 0;
00101   return cca;
00102 }
00103 
00104 int main(int argc, char **argv)
00105 {
00106   ros::init(argc, argv, "call_cca", ros::init_options::AnonymousName);
00107 
00108   ros::AsyncSpinner spinner(1);
00109   spinner.start();
00110 
00111   ros::NodeHandle nh;
00112   ros::service::waitForService(CONSTRUCT_CONSTRAINT_APPROXIMATION_SERVICE_NAME);
00113   ros::ServiceClient cca_service_client = nh.serviceClient<moveit_msgs::ConstructConstraintApproximation>(CONSTRUCT_CONSTRAINT_APPROXIMATION_SERVICE_NAME);
00114 
00115   moveit_msgs::ConstructConstraintApproximation::Request req = getDualArmConstraint();
00116   moveit_msgs::ConstructConstraintApproximation::Request res;
00117   if (cca_service_client.call(req, res))
00118     ROS_INFO("Done");
00119   else
00120     ROS_ERROR("Failed");
00121 
00122   return 0;
00123 }


pr2_ompl_planning_tests
Author(s): Ioan Sucan
autogenerated on Mon Oct 6 2014 11:13:17