20 from actionlib
import SimpleActionClient
21 from control_msgs.msg
import FollowJointTrajectoryAction, \
22 FollowJointTrajectoryGoal
23 from moveit_commander
import MoveGroupCommander, RobotCommander, \
24 PlanningSceneInterface
25 from moveit_msgs.msg
import RobotTrajectory, PositionIKRequest
26 from sensor_msgs.msg
import JointState
27 import geometry_msgs.msg
28 from sr_robot_msgs.srv
import RobotTeachMode, RobotTeachModeRequest, \
29 RobotTeachModeResponse
31 from moveit_msgs.srv
import GetPositionIK
32 from moveit_msgs.srv
import ListRobotStatesInWarehouse
as ListStates
33 from moveit_msgs.srv
import GetRobotStateFromWarehouse
as GetState
34 from moveit_msgs.msg
import OrientationConstraint, Constraints
36 from trajectory_msgs.msg
import JointTrajectoryPoint, JointTrajectory
37 from math
import radians
39 from moveit_msgs.srv
import GetPositionFK
40 from std_msgs.msg
import Header
59 Base class for hand and arm commanders. 64 Initialize MoveGroupCommander object. 65 @param name - name of the MoveIt group. 82 rospy.Subscriber(
"joint_states", JointState,
93 rospy.wait_for_service(
'compute_ik')
94 self.
_compute_ik = rospy.ServiceProxy(
'compute_ik', GetPositionIK)
95 self.
_forward_k = rospy.ServiceProxy(
'compute_fk', GetPositionFK)
97 controller_list_param = rospy.get_param(
"/move_group/controller_list")
100 self.
_controllers = {item[
"name"]: item[
"joints"]
for item
in controller_list_param}
107 threading.Thread(
None, rospy.spin)
111 Sets the planner_id used for all future planning requests. 112 @param planner_id - The string for the planner id, set to None to clear. 114 self._move_group_commander.set_planner_id(planner_id)
117 self._move_group_commander.set_num_planning_attempts(num_planning_attempts)
121 Specifies the amount of time to be used for motion planning. 122 Some planning algorithms might require more time than others to compute 125 self._move_group_commander.set_planning_time(seconds)
133 fk_link_names = [self._move_group_commander.get_end_effector_link()]
134 header.frame_id = self._move_group_commander.get_pose_reference_frame()
135 response = self.
_forward_k(header, fk_link_names, state)
136 return response.pose_stamped[0]
140 @return - returns the name of the frame wrt which the motion planning 143 return self._move_group_commander.get_planning_frame()
147 Set the reference frame to assume for poses of end-effectors. 148 @param reference_frame - name of the frame. 150 self._move_group_commander.set_pose_reference_frame(reference_frame)
161 Set a scaling factor for optionally reducing the maximum joint velocity. 162 @param value - Allowed values are in (0,1]. 164 self._move_group_commander.set_max_velocity_scaling_factor(value)
168 Set a scaling factor for optionally reducing the maximum joint accelaration. 169 @param value - Allowed values are in (0,1]. 171 self._move_group_commander.set_max_acceleration_scaling_factor(value)
175 Enable/disable looking around for motion planning. 176 @param value - boolean. 178 self._move_group_commander.allow_looking(value)
182 Enable/disable replanning in case new obstacles are detected 183 while executing a plan. 184 @param value - boolean. 186 self._move_group_commander.allow_replanning(value)
190 Executes the last plan made. 193 self._move_group_commander.execute(self.
__plan)
196 rospy.logwarn(
"No plans were made, not executing anything.")
200 Executes a given plan. 201 @param plan - RobotTrajectory msg that contains the trajectory 202 to the set goal state. 205 self._move_group_commander.execute(plan)
208 rospy.logwarn(
"Plan is not valid, not executing anything.")
211 angle_degrees=
False):
213 Set target of the robot's links and moves to it. 214 @param joint_states - dictionary with joint name and value. It can 215 contain only joints values of which need to be changed. 216 @param wait - should method wait for movement end or not. 217 @param angle_degrees - are joint_states in degrees or not. 219 joint_states_cpy = copy.deepcopy(joint_states)
222 joint_states_cpy.update((joint, radians(i))
223 for joint, i
in joint_states_cpy.items())
224 self._move_group_commander.set_start_state_to_current_state()
225 self._move_group_commander.set_joint_value_target(joint_states_cpy)
226 self._move_group_commander.go(wait=wait)
230 Set target of the robot's links and plans. 231 @param joint_states - dictionary with joint name and value. It can 232 contain only joints values of which need to be changed. 233 @param angle_degrees - are joint_states in degrees or not. 234 @param custom_start_state - specify a start state different than the current state 235 This is a blocking method. 236 @return - motion plan (RobotTrajectory msg) that contains the trajectory to the set goal state. 238 joint_states_cpy = copy.deepcopy(joint_states)
241 joint_states_cpy.update((joint, radians(i))
242 for joint, i
in joint_states_cpy.items())
243 if custom_start_state
is None:
244 self._move_group_commander.set_start_state_to_current_state()
246 self._move_group_commander.set_start_state(custom_start_state)
247 self._move_group_commander.set_joint_value_target(joint_states_cpy)
248 self.
__plan = self._move_group_commander.plan()
253 Checks if current plan contains a valid trajectory 255 return (self.
__plan is not None and len(self.__plan.joint_trajectory.points) > 0)
259 Checks if given plan contains a valid trajectory 261 return (plan
is not None and len(plan.joint_trajectory.points) > 0)
265 Returns given plan quality calculated by a weighted sum of angles traveled by each 266 of the joints, giving higher weights to the joints closer to the base of the robot, 267 thus penalizing them as smallmovements of these joints will result in bigger movements 268 of the end effector. Formula: 270 PQ = sum_(i=0)^(n-1){w_i * abs(x_i - x_(i0)}, where: 272 n - number of robot's joints, 273 w - weight specified for each joint, 274 x - joint's goal position, 275 x_0 - joint's initial position. 277 The lower the value, the better the plan. 283 num_of_joints = len(plan.joint_trajectory.points[0].positions)
284 weights = numpy.array(sorted(range(1, num_of_joints + 1), reverse=
True))
285 plan_array = numpy.empty(shape=(len(plan.joint_trajectory.points),
288 for i, point
in enumerate(plan.joint_trajectory.points):
289 plan_array[i] = point.positions
291 deltas = abs(numpy.diff(plan_array, axis=0))
292 sum_deltas = numpy.sum(deltas, axis=0)
293 sum_deltas_weighted = sum_deltas * weights
294 plan_quality = float(numpy.sum(sum_deltas_weighted))
301 if plan_quality > medium_threshold:
302 rospy.logwarn(
"Low plan quality! Value: {}".format(plan_quality))
304 elif (plan_quality > good_threshold
and 305 plan_quality < medium_threshold):
306 rospy.loginfo(
"Medium plan quality. Value: {}".format(plan_quality))
308 elif plan_quality < good_threshold:
309 rospy.loginfo(
"Good plan quality. Value: {}".format(plan_quality))
320 Set a joint configuration by name. 321 @param name - name of the target which must correspond to a name defined, 322 either in the srdf or in the mongo warehouse database. 323 @return - bool to confirm that the target has been correctly set. 326 self._move_group_commander.set_named_target(name)
330 active_names = self._move_group_commander._g.get_active_joints()
331 joints = response.state.joint_state.name
332 positions = response.state.joint_state.position
335 for n, this_name
in enumerate(joints):
336 if this_name
in active_names:
337 js[this_name] = positions[n]
338 self._move_group_commander.set_joint_value_target(js)
340 rospy.logerr(
"Unknown named state '%s'..." % name)
346 Get the joint angles for targets specified by name. 347 @param name - @param name - name of the target which must correspond to a name defined, 348 either in the srdf or in the mongo warehouse database. 349 @return - joint values of the named target. 354 output = self._move_group_commander._g.get_named_target_values(str(name))
360 for x, n
in enumerate(js.name):
361 if n
in self._move_group_commander._g.get_joints():
362 output[n] = js.position[x]
365 rospy.logerr(
"No target named %s" % name)
372 return self._move_group_commander.get_end_effector_link()
376 Get the current pose of the end effector. 377 @param reference_frame - The desired reference frame in which end effector pose should be returned. 378 If none is passed, it will use the planning frame as reference. 379 @return - geometry_msgs.msg.Pose() - current pose of the end effector. 381 if reference_frame
is not None:
383 trans = self.tf_buffer.lookup_transform(reference_frame,
384 self._move_group_commander.get_end_effector_link(),
387 current_pose = geometry_msgs.msg.Pose()
388 current_pose.position.x = trans.transform.translation.x
389 current_pose.position.y = trans.transform.translation.y
390 current_pose.position.z = trans.transform.translation.z
391 current_pose.orientation.x = trans.transform.rotation.x
392 current_pose.orientation.y = trans.transform.rotation.y
393 current_pose.orientation.z = trans.transform.rotation.z
394 current_pose.orientation.w = trans.transform.rotation.w
396 except (tf2_ros.LookupException, tf2_ros.ConnectivityException, tf2_ros.ExtrapolationException):
397 rospy.logwarn(
"Couldn't get the pose from " + self._move_group_commander.get_end_effector_link() +
398 " in " + reference_frame +
" reference frame")
401 return self._move_group_commander.get_current_pose().pose
405 Get the current joint state of the group being used. 406 @return - a dictionary with the joint names as keys and current joint values. 408 joint_names = self._move_group_commander._g.get_active_joints()
409 joint_values = self._move_group_commander._g.get_current_joint_values()
411 return dict(zip(joint_names, joint_values))
415 Get the current joint state of the group being used, enforcing that they are within each joint limits. 416 @return - a dictionary with the joint names as keys and current joint values. 418 current = self._move_group_commander._g.get_current_state_bounded()
419 names = self._move_group_commander._g.get_active_joints()
420 output = {n: current[n]
for n
in names
if n
in current}
425 return self._move_group_commander._g.get_current_state_bounded()
429 Set target of the robot's links and moves to it 430 @param name - name of the target pose defined in SRDF 431 @param wait - should method wait for movement end or not 433 self._move_group_commander.set_start_state_to_current_state()
435 self._move_group_commander.go(wait=wait)
439 Set target of the robot's links and plans 440 This is a blocking method. 441 @param name - name of the target pose defined in SRDF. 442 @param custom_start_state - specify a start state different than the current state. 443 @return - a motion plan (RobotTrajectory msg) that contains the trajectory to the named target. 445 if custom_start_state
is None:
446 self._move_group_commander.set_start_state_to_current_state()
448 self._move_group_commander.set_start_state(custom_start_state)
450 self.
__plan = self._move_group_commander.plan()
454 list_srv = rospy.ServiceProxy(
"list_robot_states", ListStates)
457 except rospy.ServiceException
as exc:
458 rospy.logwarn(
"Couldn't access warehouse: " + str(exc))
468 return self._move_group_commander._g.get_named_targets()
472 Get the complete list of named targets, from SRDF 473 as well as warehouse poses if available. 474 @return - list of strings containing names of targets. 480 Returns joints position. 481 @return - dictionary with joints positions. 488 Returns joints velocities 489 @return - dictionary with joints velocities. 496 Returns joints effort. 497 @return - dictionary with joints efforts. 505 @return - JointState message 512 Moves robot through all joint states with specified timeouts. 513 @param joint_trajectory - JointTrajectory class object. Represents 514 trajectory of the joints which would be executed. 516 plan = RobotTrajectory()
517 plan.joint_trajectory = joint_trajectory
518 self._move_group_commander.execute(plan)
522 Makes joint value trajectory from specified by named poses (either from 523 SRDF or from warehouse). 524 @param trajectory - list of waypoints, each waypoint is a dict with 525 the following elements (n.b either name or joint_angles is required) 526 - name -> the name of the way point 527 - joint_angles -> a dict of joint names and angles 528 - interpolate_time -> time to move from last wp 529 - pause_time -> time to wait at this wp 530 - degrees -> set to true if joint_angles is specified in degrees. Assumed false if absent. 534 joint_trajectory = JointTrajectory()
535 joint_names = current.keys()
536 joint_trajectory.joint_names = joint_names
538 start = JointTrajectoryPoint()
539 start.positions = current.values()
540 start.time_from_start = rospy.Duration.from_sec(0.001)
541 joint_trajectory.points.append(start)
543 time_from_start = 0.0
545 for wp
in trajectory:
547 joint_positions =
None 548 if 'name' in wp.keys():
550 elif 'joint_angles' in wp.keys():
551 joint_positions = copy.deepcopy(wp[
'joint_angles'])
552 if 'degrees' in wp.keys()
and wp[
'degrees']:
553 for joint, angle
in joint_positions.iteritems():
554 joint_positions[joint] = radians(angle)
556 if joint_positions
is None:
557 rospy.logerr(
"Invalid waypoint. Must contain valid name for named target or dict of joint angles.")
562 for n
in joint_names:
563 new_positions[n] = joint_positions[n]
if n
in joint_positions
else current[n]
565 trajectory_point = JointTrajectoryPoint()
566 trajectory_point.positions = [new_positions[n]
for n
in joint_names]
568 current = new_positions
570 time_from_start += wp[
'interpolate_time']
571 trajectory_point.time_from_start = rospy.Duration.from_sec(time_from_start)
572 joint_trajectory.points.append(trajectory_point)
574 if 'pause_time' in wp
and wp[
'pause_time'] > 0:
575 extra = JointTrajectoryPoint()
576 extra.positions = trajectory_point.positions
577 time_from_start += wp[
'pause_time']
578 extra.time_from_start = rospy.Duration.from_sec(time_from_start)
579 joint_trajectory.points.append(extra)
581 return joint_trajectory
585 Sends a trajectory of all active joints at their current position. 586 This stops the robot. 591 trajectory_point = JointTrajectoryPoint()
592 trajectory_point.positions = current.values()
593 trajectory_point.time_from_start = rospy.Duration.from_sec(0.1)
595 trajectory = JointTrajectory()
596 trajectory.points.append(trajectory_point)
597 trajectory.joint_names = current.keys()
603 Moves robot through trajectory specified by named poses, either from 604 SRDF or from warehouse. Runs trajectory directly via contoller. 605 @param trajectory - list of waypoints, each waypoint is a dict with 606 the following elements: 607 - name -> the name of the way point 608 - interpolate_time -> time to move from last wp 609 - pause_time -> time to wait at this wp 612 if joint_trajectory
is not None:
617 Moves robot through trajectory specified by named poses, either from 618 SRDF or from warehouse. Runs trajectory via moveit. 619 @param trajectory - list of waypoints, each waypoint is a dict with 620 the following elements: 621 - name -> the name of the way point 622 - interpolate_time -> time to move from last wp 623 - pause_time -> time to wait at this wp 626 if joint_trajectory
is not None:
631 Specify a target position for the end-effector and moves to it. 632 @param xyz - new position of end-effector. 633 @param end_effector_link - name of the end effector link. 634 @param wait - should method wait for movement end or not. 636 self._move_group_commander.set_start_state_to_current_state()
637 self._move_group_commander.set_position_target(xyz, end_effector_link)
638 self._move_group_commander.go(wait=wait)
642 Specify a target position for the end-effector and plans. 643 This is a blocking method. 644 @param xyz - new position of end-effector. 645 @param end_effector_link - name of the end effector link. 646 @param custom_start_state - specify a start state different than the current state. 648 if custom_start_state
is None:
649 self._move_group_commander.set_start_state_to_current_state()
651 self._move_group_commander.set_start_state(custom_start_state)
652 self._move_group_commander.set_position_target(xyz, end_effector_link)
653 self.
__plan = self._move_group_commander.plan()
657 Specify a target pose for the end-effector and moves to it 658 @param pose - new pose of end-effector: a Pose message, a PoseStamped 659 message or a list of 6 floats: [x, y, z, rot_x, rot_y, rot_z] or a list 660 of 7 floats [x, y, z, qx, qy, qz, qw]. 661 @param end_effector_link - name of the end effector link. 662 @param wait - should method wait for movement end or not. 664 self._move_group_commander.set_start_state_to_current_state()
665 self._move_group_commander.set_pose_target(pose, end_effector_link)
666 self._move_group_commander.go(wait=wait)
668 def plan_to_pose_target(self, pose, end_effector_link="", alternative_method=False, custom_start_state=None):
670 Specify a target pose for the end-effector and plans. 671 This is a blocking method. 672 @param pose - new pose of end-effector: a Pose message, a PoseStamped 673 message or a list of 6 floats: [x, y, z, rot_x, rot_y, rot_z] or a list 674 of 7 floats [x, y, z, qx, qy, qz, qw]. 675 @param end_effector_link - name of the end effector link. 676 @param alternative_method - use set_joint_value_target instead of set_pose_target. 677 @param custom_start_state - specify a start state different than the current state. 679 if custom_start_state
is None:
680 self._move_group_commander.set_start_state_to_current_state()
682 self._move_group_commander.set_start_state(custom_start_state)
683 if alternative_method:
684 self._move_group_commander.set_joint_value_target(pose, end_effector_link)
686 self._move_group_commander.set_pose_target(pose, end_effector_link)
687 self.
__plan = self._move_group_commander.plan()
692 The callback function for the topic joint_states. 693 It will store the received joint position, velocity and efforts 694 information into dictionaries. 695 @param joint_state - the message containing the joints data. 700 zip(joint_state.name,
701 joint_state.position)}
703 zip(joint_state.name,
704 joint_state.velocity)}
706 zip(joint_state.name, joint_state.effort)}
710 Sets up an action client to communicate with the trajectory controller. 714 for controller_name
in controller_list.keys():
716 service_name = controller_name +
"/follow_joint_trajectory" 718 FollowJointTrajectoryAction)
719 if self.
_clients[controller_name].wait_for_server(timeout=rospy.Duration(4))
is False:
720 err_msg =
'Failed to connect to action server ({}) in 4 sec'.format(service_name)
721 rospy.logwarn(err_msg)
724 wait=
True, angle_degrees=
False):
726 Set target of the robot's links and moves to it. 727 @param joint_states - dictionary with joint name and value. It can 728 contain only joints values of which need to be changed. 729 @param time - time in s (counting from now) for the robot to reach the 730 target (it needs to be greater than 0.0 for it not to be rejected by 731 the trajectory controller). 732 @param wait - should method wait for movement end or not. 733 @param angle_degrees - are joint_states in degrees or not. 738 joint_states_cpy = copy.deepcopy(joint_states)
741 joint_states_cpy.update((joint, radians(i))
742 for joint, i
in joint_states_cpy.items())
746 goal = FollowJointTrajectoryGoal()
747 goal.trajectory.joint_names = []
748 point = JointTrajectoryPoint()
751 for x
in joint_states_cpy.keys():
752 if x
in controller_joints:
753 goal.trajectory.joint_names.append(x)
754 point.positions.append(joint_states_cpy[x])
756 point.time_from_start = rospy.Duration.from_sec(time)
758 goal.trajectory.points = [point]
760 goals[controller] = goal
767 for i
in self._clients.keys():
768 if not self.
_clients[i].wait_for_result():
769 rospy.loginfo(
"Trajectory not completed")
772 if controller
is not None:
775 for controller_running
in self._action_running.values():
776 if controller_running:
787 goals[client],
lambda terminal_state, result: self.
_action_done_cb(client, terminal_state, result))
791 Moves robot through all joint states with specified timeouts. 792 @param joint_trajectory - JointTrajectory class object. Represents 793 trajectory of the joints which would be executed. 794 @param wait - should method wait for movement end or not. 799 goal = FollowJointTrajectoryGoal()
800 goal.trajectory = copy.deepcopy(joint_trajectory)
802 indices_of_joints_in_this_controller = []
804 for i, joint
in enumerate(joint_trajectory.joint_names):
805 if joint
in controller_joints:
806 indices_of_joints_in_this_controller.append(i)
808 goal.trajectory.joint_names = [
809 joint_trajectory.joint_names[i]
for i
in indices_of_joints_in_this_controller]
811 for point
in goal.trajectory.points:
813 point.positions = [point.positions[i]
for i
in indices_of_joints_in_this_controller]
815 point.velocities = [point.velocities[i]
for i
in indices_of_joints_in_this_controller]
817 point.effort = [point.effort[i]
for i
in indices_of_joints_in_this_controller]
819 goals[controller] = goal
826 for i
in self._clients.keys():
827 if not self.
_clients[i].wait_for_result():
828 rospy.loginfo(
"Trajectory not completed")
831 eef_step=0.005, jump_threshold=0.0, custom_start_state=
None):
833 Specify a set of waypoints for the end-effector and plans. 834 This is a blocking method. 835 @param reference_frame - the reference frame in which the waypoints are given. 836 @param waypoints - an array of poses of end-effector. 837 @param eef_step - configurations are computed for every eef_step meters. 838 @param jump_threshold - maximum distance in configuration space between consecutive points in the 840 @param custom_start_state - specify a start state different than the current state. 841 @return - motion plan (RobotTrajectory msg) that contains the trajectory to the set wayapoints targets. 843 if custom_start_state
is None:
844 self._move_group_commander.set_start_state_to_current_state()
846 self._move_group_commander.set_start_state(custom_start_state)
847 old_frame = self._move_group_commander.get_pose_reference_frame()
848 if reference_frame
is not None:
850 self.
__plan, fraction = self._move_group_commander.compute_cartesian_path(waypoints, eef_step, jump_threshold)
852 return self.
__plan, fraction
856 Activates/deactivates the teach mode for the robot. 857 Activation: stops the the trajectory controllers for the robot, and 858 sets it to teach mode. 859 Deactivation: stops the teach mode and starts trajectory controllers 861 Currently this method blocks for a few seconds when called on a hand, 862 while the hand parameters are reloaded. 863 @param teach - bool to activate or deactivate teach mode 867 mode = RobotTeachModeRequest.TEACH_MODE
869 mode = RobotTeachModeRequest.TRAJECTORY_MODE
874 Make and execute a plan from the current state to the first state in an pre-existing trajectory. 875 @param trajectory - moveit_msgs/JointTrajectory. 876 @param wait - Bool to specify if movement should block untill finished. 879 if len(trajectory.points) <= 0:
880 rospy.logerr(
"Trajectory has no points in it, can't reverse...")
883 first_point = trajectory.points[0]
884 end_state = dict(zip(trajectory.joint_names, first_point.positions))
889 teach_mode_client = rospy.ServiceProxy(
'/teach_mode', RobotTeachMode)
891 req = RobotTeachModeRequest()
892 req.teach_mode = mode
895 resp = teach_mode_client(req)
896 if resp.result == RobotTeachModeResponse.ERROR:
897 rospy.logerr(
"Failed to change robot %s to mode %d", robot,
900 rospy.loginfo(
"Changed robot %s to mode %d Result = %d", robot,
902 except rospy.ServiceException:
903 rospy.logerr(
"Failed to call service teach_mode")
905 def get_ik(self, target_pose, avoid_collisions=False, joint_states=None, ik_constraints=None):
908 Computes the inverse kinematics for a given pose. It returns a JointState. 909 @param target_pose - A given pose of type PoseStamped. 910 @param avoid_collisions - Find an IK solution that avoids collisions. By default, this is false. 911 @param joint_states - initial joint configuration of type JointState from which the IK solution is computed. 912 If set to None, the current joint state is retrieved automatically. 913 @param ik_constraints - Set constraints of type Constraints for computing the IK solution. 915 service_request = PositionIKRequest()
916 service_request.group_name = self.
_name 917 service_request.ik_link_name = self._move_group_commander.get_end_effector_link()
918 service_request.pose_stamped = target_pose
919 service_request.timeout.secs = 0.5
920 service_request.avoid_collisions = avoid_collisions
921 if ik_constraints
is not None:
922 service_request.constraints = ik_constraints
923 if joint_states
is None:
926 service_request.robot_state.joint_state = joint_states
929 resp = self.
_compute_ik(ik_request=service_request)
931 if resp.error_code.val != 1:
932 if resp.error_code.val == -10:
933 rospy.logerr(
"Unreachable point: Start state in collision")
934 elif resp.error_code.val == -12:
935 rospy.logerr(
"Unreachable point: Goal state in collision")
936 elif resp.error_code.val == -31:
937 rospy.logerr(
"Unreachable point: No IK solution")
939 rospy.logerr(
"Unreachable point (error: %s)" % resp.error_code)
942 return resp.solution.joint_state
944 except rospy.ServiceException
as e:
945 rospy.logerr(
"Service call failed: %s" % e)
948 time=0.002, wait=
True, ik_constraints=
None):
950 Specify a target pose for the end-effector and moves to it. 951 @param target_pose - new pose of end-effector: a Pose message, a PoseStamped 952 message or a list of 6 floats: [x, y, z, rot_x, rot_y, rot_z] or a list 953 of 7 floats [x, y, z, qx, qy, qz, qw]. 954 @param avoid_collisions - Find an IK solution that avoids collisions. By default, this is false. 955 @param time - time in s (counting from now) for the robot to reach the 956 target (it needs to be greater than 0.0 for it not to be rejected by 957 the trajectory controller). 958 @param wait - should method wait for movement end or not. 959 @param ik_constraints - Set constraints of type Constraints for computing the IK solution. 961 joint_state = self.
get_ik(target_pose, avoid_collisions, ik_constraints=ik_constraints)
962 if joint_state
is not None:
963 active_joints = self._move_group_commander.get_active_joints()
964 current_indices = [i
for i, x
in enumerate(joint_state.name)
if any(thing
in x
for thing
in active_joints)]
965 current_names = [joint_state.name[i]
for i
in current_indices]
966 current_positions = [joint_state.position[i]
for i
in current_indices]
967 state_as_dict = dict(zip(current_names, current_positions))
def plan_to_named_target(self, name, custom_start_state=None)
def move_to_named_target(self, name, wait=True)
def get_end_effector_pose_from_named_state(self, name)
def change_teach_mode(mode, robot)
def get_planning_frame(self)
def move_to_pose_value_target_unsafe(self, target_pose, avoid_collisions=False, time=0.002, wait=True, ik_constraints=None)
def get_end_effector_link(self)
def refresh_named_targets(self)
def check_given_plan_is_valid(self, plan)
def get_named_target_joint_values(self, name)
def __init__(self, value)
def plan_to_pose_target(self, pose, end_effector_link="", alternative_method=False, custom_start_state=None)
def set_named_target(self, name)
def execute_plan(self, plan)
def get_ik(self, target_pose, avoid_collisions=False, joint_states=None, ik_constraints=None)
def run_named_trajectory(self, trajectory)
def run_joint_trajectory_unsafe(self, joint_trajectory, wait=True)
def set_teach_mode(self, teach)
def get_joints_velocity(self)
def get_current_state_bounded(self)
def plan_to_waypoints_target(self, waypoints, reference_frame=None, eef_step=0.005, jump_threshold=0.0, custom_start_state=None)
def _action_done_cb(self, controller, terminal_state, result)
def set_pose_reference_frame(self, reference_frame)
def set_max_acceleration_scaling_factor(self, value)
def get_robot_state_bounded(self)
def named_target_in_srdf(self, name)
def allow_looking(self, value)
def run_named_trajectory_unsafe(self, trajectory, wait=False)
def set_max_velocity_scaling_factor(self, value)
def make_named_trajectory(self, trajectory)
def move_to_trajectory_start(self, trajectory, wait=True)
def move_to_position_target(self, xyz, end_effector_link="", wait=True)
def _call_action(self, goals)
def evaluate_given_plan(self, plan)
def get_joints_position(self)
def get_current_state(self)
def set_planner_id(self, planner_id)
def set_num_planning_attempts(self, num_planning_attempts)
def move_to_pose_target(self, pose, end_effector_link="", wait=True)
def get_named_targets(self)
def run_joint_trajectory(self, joint_trajectory)
def _set_plan(self, plan)
def __get_srdf_names(self)
def _get_joints_effort(self)
def evaluate_plan_quality(self, plan_quality, good_threshold=20, medium_threshold=50)
def send_stop_trajectory_unsafe(self)
def move_to_joint_value_target(self, joint_states, wait=True, angle_degrees=False)
def allow_replanning(self, value)
def _set_up_action_client(self, controller_list)
def move_to_joint_value_target_unsafe(self, joint_states, time=0.002, wait=True, angle_degrees=False)
def __get_warehouse_names(self)
def plan_to_position_target(self, xyz, end_effector_link="", custom_start_state=None)
def set_planning_time(self, seconds)
def _joint_states_callback(self, joint_state)
def get_end_effector_pose_from_state(self, state)
def plan_to_joint_value_target(self, joint_states, angle_degrees=False, custom_start_state=None)
def action_is_running(self, controller=None)
def get_joints_state(self)
def get_current_pose(self, reference_frame=None)
def check_plan_is_valid(self)