def ik_solver_init(self):
        # Params
        self.poses = None

        # Reference frame for the trajectory
        self.reference_frame = 'base_link'

        # Joint names of the arm
        self.joint_names = [
            'arm_joint_1', 'arm_joint_2', 'arm_joint_3', 'arm_joint_4',
            'arm_joint_5'
        ]

        # Move group for MoveIt!
        move_group = 'move_group'

        client = actionlib.SimpleActionClient(move_group,
                                              moveit_msgs.msg.MoveGroupAction)
        rospy.loginfo("Waiting for '{0}' server".format(move_group))
        client.wait_for_server()
        rospy.loginfo("Found server '{0}'".format(move_group))

        # Name of the group to compute the inverse kinematics
        self.arm = 'arm_1'
        self.group = moveit_commander.MoveGroupCommander(self.arm)

        # Kinematics class to compute the inverse kinematics
        self.kinematics = kinematics.Kinematics(self.arm)
    def __init__(self):

        # params
        self.event = None
        self.goal_pose = None
        self.goal_pose_array = None

        # node cycle rate (in hz)
        self.loop_rate = rospy.Rate(rospy.get_param('~loop_rate', 10.0))

        # publishers
        self.event_out = rospy.Publisher("~event_out",
                                         std_msgs.msg.String,
                                         queue_size=1)
        self.selected_pose = rospy.Publisher("~selected_pose",
                                             geometry_msgs.msg.PoseStamped,
                                             queue_size=1)
        self.joint_configuration = rospy.Publisher(
            "~joint_configuration",
            brics_actuator.msg.JointPositions,
            queue_size=1)

        # subscribers
        rospy.Subscriber("~event_in", std_msgs.msg.String, self.event_in_cb)
        rospy.Subscriber("~goal_pose", geometry_msgs.msg.PoseStamped,
                         self.goal_pose_cb)
        rospy.Subscriber("~goal_pose_array", geometry_msgs.msg.PoseArray,
                         self.goal_pose_array_cb)

        # wait for MoveIt!
        move_group = rospy.get_param('~move_group', None)
        assert move_group is not None, "Move group must be specified."
        client = actionlib.SimpleActionClient(move_group,
                                              moveit_msgs.msg.MoveGroupAction)
        rospy.loginfo("Waiting for '{0}' server".format(move_group))
        client.wait_for_server()
        rospy.loginfo("Found server '{0}'".format(move_group))

        # name of the group to compute the inverse kinematics
        self.arm = rospy.get_param('~arm', None)
        assert self.arm is not None, "Group to move (e.g. arm) must be specified."

        group = moveit_commander.MoveGroupCommander(self.arm)
        # joints to compute the inverse kinematics
        self.joint_uris = group.get_joints()

        # units of the joint position values
        self.units = rospy.get_param('~units', 'rad')

        # linear offset for the X, Y and Z axis.
        self.linear_offset = rospy.get_param('~linear_offset', None)

        # kinematics class to compute the inverse kinematics
        self.kinematics = kinematics.Kinematics(self.arm)

        # Time allowed for the IK solver to find a solution (in seconds).
        self.ik_timeout = rospy.get_param('~ik_timeout', 0.5)
    def __init__(self):
        # Params
        self.event = None
        self.poses = None

        # Maximum amount of poses to compute a trajectory for
        self.max_poses = rospy.get_param('~max_poses', 10)

        # Reference frame for the trajectory
        self.reference_frame = rospy.get_param('~reference_frame', None)
        assert self.reference_frame is not None, "Reference frame must be specified."

        # Joint names of the arm
        self.joint_names = rospy.get_param('~joint_names', None)
        assert self.joint_names is not None, "Joint names must be specified."

        # Move group for MoveIt!
        move_group = rospy.get_param('~move_group', None)
        assert move_group is not None, "Move group must be specified."
        client = actionlib.SimpleActionClient(move_group,
                                              moveit_msgs.msg.MoveGroupAction)
        rospy.loginfo("Waiting for '{0}' server".format(move_group))
        client.wait_for_server()
        rospy.loginfo("Found server '{0}'".format(move_group))

        # Name of the group to compute the inverse kinematics
        self.arm = rospy.get_param('~arm', None)
        assert self.arm is not None, "Group to move (e.g. arm) must be specified."

        # Kinematics class to compute the inverse kinematics
        self.kinematics = kinematics.Kinematics(self.arm)

        # Node cycle rate (in hz)
        self.loop_rate = rospy.Rate(rospy.get_param('~loop_rate', 10.0))

        # publishers
        self.event_out = rospy.Publisher("~event_out",
                                         std_msgs.msg.String,
                                         queue_size=1)
        self.trajectory = rospy.Publisher("~trajectory",
                                          trajectory_msgs.msg.JointTrajectory,
                                          queue_size=1)

        # subscribers
        rospy.Subscriber("~event_in", std_msgs.msg.String, self.event_in_cb)
        rospy.Subscriber("~poses", geometry_msgs.msg.PoseArray, self.poses_cb)