fake_group_interface.py
Go to the documentation of this file.
1 # Copyright 2015, Fetch Robotics Inc.
2 # Copyright 2011-2014, Michael Ferguson
3 # All rights reserved.
4 #
5 # Redistribution and use in source and binary forms, with or without
6 # modification, are permitted provided that the following conditions
7 # are met:
8 #
9 # * Redistributions of source code must retain the above copyright
10 # notice, this list of conditions and the following disclaimer.
11 # * Redistributions in binary form must reproduce the above
12 # copyright notice, this list of conditions and the following
13 # disclaimer in the documentation and/or other materials provided
14 # with the distribution.
15 #
16 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
17 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
18 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
19 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
20 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
21 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
22 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
24 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
25 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
26 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27 # POSSIBILITY OF SUCH DAMAGE.
28 
29 import rospy
30 from sensor_msgs.msg import JointState
31 
32 
34 class FakeGroupInterface(object):
35 
36 
37  def __init__(self, group, frame, listener=None, plan_only=False):
38  self.pub = rospy.Publisher("/move_group/fake_controller_joint_states",
39  JointState,
40  queue_size=10)
41 
42 
44  def moveToJointPosition(self, joints, positions, **kwargs):
45  msg = JointState()
46  msg.header.stamp = rospy.Time.now()
47  msg.name = joints
48  msg.position = positions
49  self.pub.publish(msg)
def moveToJointPosition(self, joints, positions, kwargs)
This is modeled such that we can use the fake interface as a drop in replacement for the real interfa...
def __init__(self, group, frame, listener=None, plan_only=False)
Signature intended to match real interface, params not used.
This provides an interface to the "fake_controller" aspects of the MoveIt demo.launch files...


moveit_python
Author(s): Michael Ferguson
autogenerated on Sat Jan 7 2023 03:09:45