import roslib roslib.update_path('visual_odometry') import rospy import math import sys import time import Image sys.path.append('lib') from stereo_utils import camera from stereo_utils.stereo import SparseStereoFrame from stereo_utils.descriptor_schemes import DescriptorSchemeCalonder, DescriptorSchemeSAD from stereo_utils.feature_detectors import FeatureDetectorFast, FeatureDetector4x4, FeatureDetectorStar, FeatureDetectorHarris from visual_odometry.pe import PoseEstimator Fx = 389.0 Fy = 389.0 Tx = 0.08923 Clx = 323.42 Crx = 323.42 Cy = 274.95 # Camera cam = camera.Camera((Fx, Fy, Tx, Clx, Crx, Cy)) # Feature Detector fd = FeatureDetectorFast(300) # Descriptor Scheme
# # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. import roslib roslib.update_path('kinematic_calibration') import rospy import sys import rosrecord filename = sys.argv[1] framecounter = 1 print "Starting Playback" f = filename keys = set() headers = [] headers_file = open("joint_names.txt", "w") pos_file = open("joint_pos.txt", "w")
#!/usr/bin/python """ usage: %(progname)s annotation.xml * Reads xml annotations for an image and extracts the polygons, each polygon outlines a hand * Converts the polygons to oriented bounding boxes, where the orientation is given by the axis going from the middle of the wrist to the middle finger. * The output format is: x, y, width, height, angle, flip where x,y is the center of the box, angle is in radians, and flip is 0 if the thumb is on the left, 1 if it is on the right """ import roslib roslib.load_manifest('hand_tracker') roslib.update_path('test_roslaunch') import unittest import numpy import cv from hand_tracker import oriented_bounding_boxes #---------------------------------------------------------------------- # Test functions #---------------------------------------------------------------------- class TestHandToBox(unittest.TestCase): def test_single_hand_outline_to_oriented_box(self): # Can add other examples: inputs = [[(140, 100), (100, 140), (60, 150), (40, 130), (20, 70), (40, 20), (90, 30)]] expected_outputs = [[ 79.952076677316299, 86.198083067092639, 142.00644025354072,
# # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. import roslib roslib.update_path('actionlib') import sys import unittest import rospy from actionlib_msgs.msg import * from actionlib import SimpleActionClient from actionlib.msg import TestAction, TestGoal class TestSimpleActionClient(unittest.TestCase): def testsimple(self): client = SimpleActionClient('reference_action', TestAction) self.assert_( client.wait_for_action_server_to_start(rospy.Duration(10.0)), 'Could not connect to the action server')