test_nxopen.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 # -*- coding: utf-8 -*-
00003 
00004 # Software License Agreement (BSD License)
00005 #
00006 # Copyright (c) 2013, Tokyo Opensource Robotics Kyokai Association
00007 # All rights reserved.
00008 #
00009 # Redistribution and use in source and binary forms, with or without
00010 # modification, are permitted provided that the following conditions
00011 # are met:
00012 #
00013 #  * Redistributions of source code must retain the above copyright
00014 #    notice, this list of conditions and the following disclaimer.
00015 #  * Redistributions in binary form must reproduce the above
00016 #    copyright notice, this list of conditions and the following
00017 #    disclaimer in the documentation and/or other materials provided
00018 #    with the distribution.
00019 #  * Neither the name of Tokyo Opensource Robotics Kyokai Association. nor the
00020 #    names of its contributors may be used to endorse or promote products
00021 #    derived from this software without specific prior written permission.
00022 #
00023 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034 # POSSIBILITY OF SUCH DAMAGE.
00035 #
00036 # Author: Isaac Isao Saito
00037 
00038 # This should come earlier than later import.
00039 # See http://code.google.com/p/rtm-ros-robotics/source/detail?r=6773
00040 import unittest
00041 
00042 from hrpsys import rtm
00043 from nextage_ros_bridge import nextage_client
00044 
00045 _ARMGROUP_TESTED = 'larm'
00046 _LINK_TESTED = 'LARM_JOINT5'
00047 _GOINITIAL_TIME_MIDSPEED = 3  # second
00048 _NUM_CARTESIAN_ITERATION = 300
00049 _PKG = 'nextage_ros_bridge'
00050 
00051 
00052 class TestNextageopen(unittest.TestCase):
00053     '''
00054     Test NextageClient with rostest.
00055     '''
00056 
00057     @classmethod
00058     def setUpClass(self):
00059 
00060         modelfile = '/opt/jsk/etc/HIRONX/model/main.wrl'
00061         rtm.nshost = 'nxc100'
00062         robotname = "RobotHardware0"
00063 
00064         self._robot = nextage_client.NextageClient()
00065         self._robot.init(robotname=robotname, url=modelfile)
00066 
00067         self._robot.goInitial(_GOINITIAL_TIME_MIDSPEED)
00068 
00069 #    def test_set_relative_x(self):
00070     def _set_relative(self, dx=0, dy=0, dz=0):
00071         #print('Start moving dx={0}, dy={0}, dz={0}'.format(dx, dy, dz))
00072         self._robot.seq_svc.setMaxIKError(0.00001, 0.01)
00073         posi_prev = self._robot.getCurrentPosition(_LINK_TESTED)
00074         for i in range(_NUM_CARTESIAN_ITERATION):
00075             self._robot.setTargetPoseRelative(
00076                 _ARMGROUP_TESTED, _LINK_TESTED, dx, dy, dz, tm=0.15)
00077             #print('   joint=', nxc.getJointAngles()[3:9])
00078         posi_post = self._robot.getCurrentPosition(_LINK_TESTED)
00079 
00080         diff_result = posi_post
00081         for i in range(len(posi_prev)):
00082             diff_result[i] = posi_prev[i] - posi_post[i]
00083         print('Position diff={}'.format(diff_result))
00084         return True
00085 
00086     def test_set_targetpose_relative_dx(self):
00087         self._robot.goInitial(_GOINITIAL_TIME_MIDSPEED)
00088         assert(self._set_relative(dx=0.0001))
00089 
00090     def test_set_targetpose_relative_dy(self):
00091         self._robot.goInitial(_GOINITIAL_TIME_MIDSPEED)
00092         assert(self._set_relative(dy=0.0001))
00093 
00094     def test_set_targetpose_relative_dz(self):
00095         self._robot.goInitial(_GOINITIAL_TIME_MIDSPEED)
00096         assert(self._set_relative(dz=0.0001))
00097 
00098 if __name__ == '__main__':
00099     import rostest
00100     rostest.rosrun(_PKG, 'test_nxopen', TestNextageopen)


nextage_ros_bridge
Author(s): Isaac Isao Saito
autogenerated on Mon Oct 6 2014 07:22:37