30 from sensor_msgs.msg
import JointState
37 def __init__(self, group, frame, listener=None, plan_only=False):
38 self.
pub = rospy.Publisher(
"/move_group/fake_controller_joint_states",
46 msg.header.stamp = rospy.Time.now()
48 msg.position = positions
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...