19 from copy
import deepcopy
22 from geometry_msgs.msg
import PoseStamped
23 from moveit_commander
import MoveGroupCommander, PlanningSceneInterface
30 _transform_listener =
None 31 _transform_listener_creation_lock = threading.Lock()
34 _mgc_dict_creation_lock = threading.Lock()
37 _psi_creation_lock = threading.Lock()
41 Gets the transform listener for this process. 42 This is needed because tf only allows one transform listener per process. Threadsafe, so 43 that two threads could call this at the same time, at it will do the right thing. 45 global _transform_listener
46 with _transform_listener_creation_lock:
47 if _transform_listener ==
None:
49 return _transform_listener
55 Gets the move_group_commander for this process. 58 with _mgc_dict_creation_lock:
59 if not group
in _mgc_dict:
60 _mgc_group = MoveGroupCommander(group)
61 _mgc_group.set_planner_id(
'RRTConnectkConfigDefault')
62 _mgc_dict[group] = _mgc_group
65 return _mgc_dict[group]
71 Gets the planning_scene_interface for this process. 74 with _psi_creation_lock:
76 _psi = PlanningSceneInterface()
83 pose.pose.position.x = 0
84 pose.pose.position.y = 0
86 pose.pose.position.z = -0.0501
87 pose.pose.orientation.x = 0
88 pose.pose.orientation.y = 0
89 pose.pose.orientation.z = 0
90 pose.pose.orientation.w = 1
91 pose.header.stamp = rospy.get_rostime()
92 pose.header.frame_id =
"base_link" 93 psi.attach_box(
"base_link",
"ground", pose, (3, 3, 0.1))
98 psi.remove_world_object(
"")
102 psi.remove_attached_object(link = attach_link, name = object_name)
103 psi.remove_world_object(object_name)
109 pose.pose.orientation.w = 1
110 pose.header.stamp = rospy.get_rostime()
111 pose.header.frame_id = link
112 psi.attach_mesh(link, name, pose, path)
116 mgc.allow_replanning(replanning)
121 print(
"Failed to plan path")
126 mgc.allow_replanning(replan)
127 mgc.set_pose_reference_frame(ref_frame)
129 mgc.allow_replanning(
False)
134 print(
"Failed to plan path")
143 mgc.set_pose_reference_frame(ref_frame)
144 (traj,frac) = mgc.compute_cartesian_path(goal_list, 0.01, 4, avoid_collisions)
152 if mgc.execute(traj):
156 print(
"Something happened during execution")
159 print(
"Failed to plan full path!")
166 cp = mgc.get_current_pose()
167 cp.header.stamp = rospy.Time()
181 ns_global_prefix =
"/script_server" 184 param_string = ns_global_prefix +
"/" + group +
"/joint_names" 185 if not rospy.has_param(param_string):
186 rospy.logerr(
"parameter %s does not exist on ROS Parameter Server, aborting...",param_string)
188 joint_names = rospy.get_param(param_string)
191 if not type(joint_names)
is list:
192 rospy.logerr(
"no valid joint_names for %s: not a list, aborting...",group)
193 print(
"joint_names are:",joint_names)
196 for i
in joint_names:
197 if not type(i)
is str:
198 rospy.logerr(
"no valid joint_names for %s: not a list of strings, aborting...",group)
199 print(
"joint_names are:",joint_names)
202 rospy.logdebug(
"accepted joint_names for group %s",group)
205 if type(parameter_name)
is str:
206 if not rospy.has_param(ns_global_prefix +
"/" + group +
"/" + parameter_name):
207 rospy.logerr(
"parameter %s does not exist on ROS Parameter Server, aborting...",ns_global_prefix +
"/" + group +
"/" + parameter_name)
209 param = rospy.get_param(ns_global_prefix +
"/" + group +
"/" + parameter_name)
211 param = parameter_name
214 if not type(param)
is list:
215 rospy.logerr(
"no valid parameter for %s: not a list, aborting...",group)
216 print(
"parameter is:",param)
220 point = param[len(param)-1]
223 if type(point)
is str:
224 if not rospy.has_param(ns_global_prefix +
"/" + group +
"/" + point):
225 rospy.logerr(
"parameter %s does not exist on ROS Parameter Server, aborting...",ns_global_prefix +
"/" + group +
"/" + point)
227 point = rospy.get_param(ns_global_prefix +
"/" + group +
"/" + point)
230 elif type(point)
is list:
231 rospy.logdebug(
"point is a list")
233 rospy.logerr(
"no valid parameter for %s: not a list of lists or strings, aborting...",group)
234 print(
"parameter is:",param)
239 if not len(point) == len(joint_names):
240 rospy.logerr(
"no valid parameter for %s: dimension should be %d and is %d, aborting...",group,len(joint_names),len(point))
241 print(
"parameter is:",param)
246 if not ((type(value)
is float)
or (type(value)
is int)):
248 rospy.logerr(
"no valid parameter for %s: not a list of float or int, aborting...",group)
249 print(
"parameter is:",param)
251 rospy.logdebug(
"accepted value %f for %s",value,group)
def clear_attached_object(attach_link, object_name=None)
def get_transform_listener()
def moveit_pose_goal(group, ref_frame, goal, replan=False)
def get_goal_from_server(group, parameter_name)
helpers
def get_move_group_commander(group)
def moveit_get_current_pose(group)
def attach_mesh_to_link(link, name, path)
def moveit_cart_goals(group, ref_frame, goal_list, avoid_collisions=True)
def get_planning_scene_interface()
def moveit_joint_goal(group, goal, replanning=False)