moveit2
The MoveIt Motion Planning Framework for ROS 2.
plan_with_constraints.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 # Software License Agreement (BSD License)
4 #
5 # Copyright (c) 2018, Houston Mechatronics, Inc.
6 # All rights reserved.
7 #
8 # Redistribution and use in source and binary forms, with or without
9 # modification, are permitted provided that the following conditions
10 # are met:
11 #
12 # * Redistributions of source code must retain the above copyright
13 # notice, this list of conditions and the following disclaimer.
14 # * Redistributions in binary form must reproduce the above
15 # copyright notice, this list of conditions and the following
16 # disclaimer in the documentation and/or other materials provided
17 # with the distribution.
18 # * Neither the name of Willow Garage, Inc. nor the names of its
19 # contributors may be used to endorse or promote products derived
20 # from this software without specific prior written permission.
21 #
22 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 # POSSIBILITY OF SUCH DAMAGE.
34 #
35 # Author: Siddharth Srivatsa
36 
37 import sys
38 import rospy
39 from moveit_commander import RobotCommander, roscpp_initialize, roscpp_shutdown
40 from moveit_msgs.msg import RobotState, Constraints
41 from geometry_msgs.msg import Pose
42 
43 if __name__ == "__main__":
44 
45  roscpp_initialize(sys.argv)
46  rospy.init_node("moveit_py_demo", anonymous=True)
47 
48  robot = RobotCommander()
49  rospy.sleep(1)
50 
51  a = robot.right_arm
52  a.set_start_state(RobotState())
53 
54  print("current pose:")
55  print(a.get_current_pose())
56  c = Constraints()
57 
58  waypoints = []
59  waypoints.append(a.get_current_pose().pose)
60 
61  # Move forward
62  wpose = Pose()
63  wpose.position.x = wpose.position.x + 0.1
64  waypoints.append(wpose)
65 
66  # Move down
67  wpose.position.z -= 0.10
68  waypoints.append(wpose)
69 
70  # Move to the side
71  wpose.position.y += 0.05
72  waypoints.append(wpose)
73 
74  plan, fraction = a.compute_cartesian_path(waypoints, 0.01, 0.0, path_constraints=c)
75  print("Plan success percent: ", fraction)
void print(PropagationDistanceField &pdf, int numX, int numY, int numZ)