def plan_cartesian_motion_async(self, callback, errback,
                                    frames_WCF, start_configuration=None, group=None, options=None):
        """Asynchronous handler of MoveIt cartesian motion planner service."""
        joint_names = options['joint_names']
        joint_types = options['joint_types']
        joint_type_by_name = dict(zip(joint_names, joint_types))

        header = Header(frame_id=options['base_link'])
        waypoints = [Pose.from_frame(frame) for frame in frames_WCF]
        joint_state = JointState(header=header,
                                 name=start_configuration.joint_names,
                                 position=start_configuration.joint_values)
        start_state = RobotState(joint_state, MultiDOFJointState(header=header), is_diff=True)

        if options.get('attached_collision_meshes'):
            for acm in options['attached_collision_meshes']:
                aco = AttachedCollisionObject.from_attached_collision_mesh(acm)
                start_state.attached_collision_objects.append(aco)

        path_constraints = convert_constraints_to_rosmsg(options.get('path_constraints'), header)

        request = dict(header=header,
                       start_state=start_state,
                       group_name=group,
                       link_name=options['link'],
                       waypoints=waypoints,
                       max_step=float(options.get('max_step', 0.01)),
                       jump_threshold=float(options.get('jump_threshold', 1.57)),
                       avoid_collisions=bool(options.get('avoid_collisions', True)),
                       path_constraints=path_constraints)

        def convert_to_trajectory(response):
            try:
                trajectory = JointTrajectory()
                trajectory.source_message = response
                trajectory.fraction = response.fraction
                trajectory.joint_names = response.solution.joint_trajectory.joint_names

                joint_types = [joint_type_by_name[name] for name in trajectory.joint_names]
                trajectory.points = convert_trajectory_points(
                    response.solution.joint_trajectory.points, joint_types)

                start_state = response.start_state.joint_state
                start_state_types = [joint_type_by_name[name] for name in start_state.name]
                trajectory.start_configuration = Configuration(start_state.position, start_state_types, start_state.name)
                trajectory.attached_collision_meshes = list(itertools.chain(*[
                    aco.to_attached_collision_meshes()
                    for aco in response.start_state.attached_collision_objects]))

                callback(trajectory)

            except Exception as e:
                errback(e)

        self.GET_CARTESIAN_PATH(self.ros_client, request, convert_to_trajectory, errback)
    def inverse_kinematics_async(self,
                                 callback,
                                 errback,
                                 frame_WCF,
                                 start_configuration=None,
                                 group=None,
                                 options=None):
        """Asynchronous handler of MoveIt IK service."""
        base_link = options['base_link']
        header = Header(frame_id=base_link)
        pose_stamped = PoseStamped(header, Pose.from_frame(frame_WCF))

        joint_state = JointState(name=start_configuration.joint_names,
                                 position=start_configuration.joint_values,
                                 header=header)
        start_state = RobotState(joint_state,
                                 MultiDOFJointState(header=header))

        if options.get('attached_collision_meshes'):
            for acm in options['attached_collision_meshes']:
                aco = AttachedCollisionObject.from_attached_collision_mesh(acm)
                start_state.attached_collision_objects.append(aco)

        constraints = convert_constraints_to_rosmsg(options.get('constraints'),
                                                    header)

        timeout_in_secs = options.get('timeout', 2)
        timeout_duration = Duration(timeout_in_secs, 0).to_data()

        ik_request = PositionIKRequest(group_name=group,
                                       robot_state=start_state,
                                       constraints=constraints,
                                       pose_stamped=pose_stamped,
                                       avoid_collisions=options.get(
                                           'avoid_collisions', True),
                                       attempts=options.get('attempts', 8),
                                       timeout=timeout_duration)

        # The field `attempts` was removed in Noetic (and higher)
        # so it needs to be removed from the message otherwise it causes a serialization error
        # https://github.com/ros-planning/moveit/pull/1288
        if self.ros_client.ros_distro not in (RosDistro.KINETIC,
                                              RosDistro.MELODIC):
            del ik_request.attempts

        def convert_to_positions(response):
            callback((response.solution.joint_state.position,
                      response.solution.joint_state.name))

        self.GET_POSITION_IK(self.ros_client, (ik_request, ),
                             convert_to_positions, errback)
    def inverse_kinematics_async(self,
                                 callback,
                                 errback,
                                 frame_WCF,
                                 start_configuration=None,
                                 group=None,
                                 options=None):
        """Asynchronous handler of MoveIt IK service."""
        base_link = options['base_link']
        header = Header(frame_id=base_link)
        pose_stamped = PoseStamped(header, Pose.from_frame(frame_WCF))

        joint_state = JointState(name=start_configuration.joint_names,
                                 position=start_configuration.values,
                                 header=header)
        start_state = RobotState(joint_state,
                                 MultiDOFJointState(header=header))

        if options.get('attached_collision_meshes'):
            for acm in options['attached_collision_meshes']:
                aco = AttachedCollisionObject.from_attached_collision_mesh(acm)
                start_state.attached_collision_objects.append(aco)

        constraints = convert_constraints_to_rosmsg(options.get('constraints'),
                                                    header)

        ik_request = PositionIKRequest(group_name=group,
                                       robot_state=start_state,
                                       constraints=constraints,
                                       pose_stamped=pose_stamped,
                                       avoid_collisions=options.get(
                                           'avoid_collisions', True),
                                       attempts=options.get('attempts', 8))

        def convert_to_positions(response):
            callback((response.solution.joint_state.position,
                      response.solution.joint_state.name))

        self.GET_POSITION_IK(self.ros_client, (ik_request, ),
                             convert_to_positions, errback)
Example #4
0
    def plan_motion_async(self,
                          callback,
                          errback,
                          goal_constraints,
                          start_configuration=None,
                          group=None,
                          options=None):
        """Asynchronous handler of MoveIt motion planner service."""
        # http://docs.ros.org/jade/api/moveit_core/html/utils_8cpp_source.html
        # TODO: if list of frames (goals) => receive multiple solutions?

        joints = options['joints']
        header = Header(frame_id=options['base_link'])
        joint_state = JointState(header=header,
                                 name=start_configuration.joint_names,
                                 position=start_configuration.joint_values)
        start_state = RobotState(joint_state,
                                 MultiDOFJointState(header=header),
                                 is_diff=True)

        if options.get('attached_collision_meshes'):
            for acm in options['attached_collision_meshes']:
                aco = AttachedCollisionObject.from_attached_collision_mesh(acm)
                start_state.attached_collision_objects.append(aco)

        # convert constraints
        goal_constraints = [
            convert_constraints_to_rosmsg(goal_constraints, header)
        ]
        path_constraints = convert_constraints_to_rosmsg(
            options.get('path_constraints'), header)
        trajectory_constraints = options.get('trajectory_constraints')

        if trajectory_constraints is not None:
            trajectory_constraints = TrajectoryConstraints(
                constraints=convert_constraints_to_rosmsg(
                    options['trajectory_constraints'], header))

        request = dict(
            start_state=start_state,
            goal_constraints=goal_constraints,
            path_constraints=path_constraints,
            trajectory_constraints=trajectory_constraints,
            planner_id=options.get('planner_id', 'RRTConnect'),
            group_name=group,
            num_planning_attempts=options.get('num_planning_attempts', 1),
            allowed_planning_time=options.get('allowed_planning_time', 2.),
            max_velocity_scaling_factor=options.get(
                'max_velocity_scaling_factor', 1.),
            max_acceleration_scaling_factor=options.get(
                'max_acceleration_scaling_factor', 1.))

        # workspace_parameters=options.get('workspace_parameters')

        def response_handler(response):
            try:
                trajectory = convert_trajectory(joints, response.trajectory,
                                                response.trajectory_start, 1.,
                                                response.planning_time,
                                                response)
                callback(trajectory)
            except Exception as e:
                errback(e)

        self.GET_MOTION_PLAN(self.ros_client, request, response_handler,
                             errback)
Example #5
0
    def plan_motion_async(self,
                          callback,
                          errback,
                          goal_constraints,
                          start_configuration=None,
                          group=None,
                          options=None):
        """Asynchronous handler of MoveIt motion planner service."""

        # http://docs.ros.org/jade/api/moveit_core/html/utils_8cpp_source.html
        # TODO: if list of frames (goals) => receive multiple solutions?
        joint_names = options['joint_names']
        joint_types = options['joint_types']
        joint_type_by_name = dict(
            zip(joint_names, joint_types)
        )  # !!! should this go somewhere else? does it already exist somewhere else?

        header = Header(frame_id=options['base_link'])
        joint_state = JointState(header=header,
                                 name=start_configuration.joint_names,
                                 position=start_configuration.joint_values)
        start_state = RobotState(joint_state,
                                 MultiDOFJointState(header=header),
                                 is_diff=True)

        if options.get('attached_collision_meshes'):
            for acm in options['attached_collision_meshes']:
                aco = AttachedCollisionObject.from_attached_collision_mesh(acm)
                start_state.attached_collision_objects.append(aco)

        # convert constraints
        goal_constraints = [
            convert_constraints_to_rosmsg(goal_constraints, header)
        ]
        path_constraints = convert_constraints_to_rosmsg(
            options.get('path_constraints'), header)
        trajectory_constraints = options.get('trajectory_constraints')

        if trajectory_constraints is not None:
            trajectory_constraints = TrajectoryConstraints(
                constraints=convert_constraints_to_rosmsg(
                    options['trajectory_constraints'], header))

        request = dict(
            start_state=start_state,
            goal_constraints=goal_constraints,
            path_constraints=path_constraints,
            trajectory_constraints=trajectory_constraints,
            planner_id=options.get('planner_id', 'RRTConnectkConfigDefault'),
            group_name=group,
            num_planning_attempts=options.get('num_planning_attempts', 1),
            allowed_planning_time=options.get('allowed_planning_time', 2.),
            max_velocity_scaling_factor=options.get(
                'max_velocity_scaling_factor', 1.),
            max_acceleration_scaling_factor=options.get(
                'max_acceleration_scaling_factor', 1.))

        # workspace_parameters=options.get('workspace_parameters')

        def convert_to_trajectory(response):
            trajectory = JointTrajectory()
            trajectory.source_message = response
            trajectory.fraction = 1.
            trajectory.joint_names = response.trajectory.joint_trajectory.joint_names
            trajectory.planning_time = response.planning_time

            joint_types = [
                joint_type_by_name[name] for name in trajectory.joint_names
            ]
            trajectory.points = convert_trajectory_points(
                response.trajectory.joint_trajectory.points, joint_types)

            start_state = response.trajectory_start.joint_state
            start_state_types = [
                joint_type_by_name[name] for name in start_state.name
            ]
            trajectory.start_configuration = Configuration(
                start_state.position, start_state_types, start_state.name)
            trajectory.attached_collision_meshes = list(
                itertools.chain(*[
                    aco.to_attached_collision_meshes() for aco in
                    response.trajectory_start.attached_collision_objects
                ]))

            callback(trajectory)

        self.GET_MOTION_PLAN(self.ros_client, request, convert_to_trajectory,
                             errback)