fake_group_interface.py
Go to the documentation of this file.
00001 # Copyright 2015, Fetch Robotics Inc.
00002 # Copyright 2011-2014, Michael Ferguson
00003 # All rights reserved.
00004 #
00005 # Redistribution and use in source and binary forms, with or without
00006 # modification, are permitted provided that the following conditions
00007 # are met:
00008 #
00009 #  * Redistributions of source code must retain the above copyright
00010 #    notice, this list of conditions and the following disclaimer.
00011 #  * Redistributions in binary form must reproduce the above
00012 #    copyright notice, this list of conditions and the following
00013 #    disclaimer in the documentation and/or other materials provided
00014 #    with the distribution.
00015 #
00016 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00017 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00018 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00019 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00020 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00021 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00022 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00023 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00024 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00025 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00026 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027 # POSSIBILITY OF SUCH DAMAGE.
00028 
00029 import rospy
00030 from sensor_msgs.msg import JointState
00031 
00032 ## @brief This provides an interface to the "fake_controller" aspects of
00033 ##        the MoveIt demo.launch files.
00034 class FakeGroupInterface(object):
00035     
00036     ## @brief Signature intended to match real interface, params not used
00037     def __init__(self, group, frame, listener=None, plan_only=False):
00038         self.pub = rospy.Publisher("/move_group/fake_controller_joint_states",
00039                                    JointState,
00040                                    queue_size=10)
00041 
00042     ## @brief This is modeled such that we can use the fake interface as a
00043     ##        drop in replacement for the real interface.
00044     def moveToJointPosition(self, joints, positions, **kwargs):
00045         msg = JointState()
00046         msg.header.stamp = rospy.Time.now()
00047         msg.name = joints
00048         msg.position = positions
00049         self.pub.publish(msg)


moveit_python
Author(s): Michael Ferguson
autogenerated on Fri Aug 26 2016 13:12:36