python_move_group.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 import unittest
00004 import numpy as np
00005 import rospy
00006 import rostest
00007 import os
00008 
00009 from moveit_ros_planning_interface._moveit_move_group_interface import MoveGroup
00010 
00011 
00012 class PythonMoveGroupTest(unittest.TestCase):
00013     PLANNING_GROUP = "manipulator"
00014 
00015     @classmethod
00016     def setUpClass(self):
00017         self.group = MoveGroup(self.PLANNING_GROUP, "robot_description")
00018 
00019     @classmethod
00020     def tearDown(self):
00021         pass
00022 
00023     def check_target_setting(self, expect, *args):
00024         if len(args) == 0:
00025             args = [expect]
00026         self.group.set_joint_value_target(*args)
00027         res = self.group.get_joint_value_target()
00028         self.assertTrue(np.all(np.asarray(res) == np.asarray(expect)),
00029                         "Setting failed for %s, values: %s" % (type(args[0]), res))
00030 
00031     def test_target_setting(self):
00032         n = self.group.get_variable_count()
00033         self.check_target_setting([0.1] * n)
00034         self.check_target_setting((0.2,) * n)
00035         self.check_target_setting(np.zeros(n))
00036         self.check_target_setting([0.3] * n, {name: 0.3 for name in self.group.get_active_joints()})
00037         self.check_target_setting([0.5] + [0.3]*(n-1), "joint_1", 0.5)
00038 
00039     def plan(self, target):
00040         self.group.set_joint_value_target(target)
00041         return self.group.compute_plan()
00042 
00043     def test_validation(self):
00044         current = np.asarray(self.group.get_current_joint_values())
00045 
00046         plan1 = self.plan(current + 0.2)
00047         plan2 = self.plan(current + 0.2)
00048 
00049         # first plan should execute
00050         self.assertTrue(self.group.execute(plan1))
00051 
00052         # second plan should be invalid now (due to modified start point) and rejected
00053         self.assertFalse(self.group.execute(plan2))
00054 
00055         # newly planned trajectory should execute again
00056         plan3 = self.plan(current)
00057         self.assertTrue(self.group.execute(plan3))
00058 
00059 
00060 if __name__ == '__main__':
00061     PKGNAME = 'moveit_ros_planning_interface'
00062     NODENAME = 'moveit_test_python_move_group'
00063     rospy.init_node(NODENAME)
00064     rostest.rosrun(PKGNAME, NODENAME, PythonMoveGroupTest)
00065 
00066     # suppress cleanup segfault
00067     os._exit(0)


planning_interface
Author(s): Ioan Sucan
autogenerated on Mon Jul 24 2017 02:22:06