Skip to content

Commit 30ffee0

Browse files
authored
Merge pull request #124 from cpaxton/feature/smartmove-constraints
adding more smartmove constraints
2 parents 813e8ee + 7dbdd3f commit 30ffee0

File tree

5 files changed

+64
-26
lines changed

5 files changed

+64
-26
lines changed

costar_predicator/predicator_landmark/src/predicator_landmark/landmark.py

Lines changed: 34 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -59,7 +59,17 @@ def get_waypoints_srv(self,req):
5959

6060
return resp
6161

62-
def get_waypoints(self,frame_type,predicates,transforms,names):
62+
def get_waypoints(self, frame_type, predicates, transforms, names, constraints):
63+
'''
64+
Parameters:
65+
-----------
66+
frame_type: object class to match when generating new frames
67+
predicates: other list of predicates to add
68+
transforms: used to generate the actual poses
69+
names: should be same size as transforms
70+
above: prunes list of transforms based on criteria, transforms should
71+
be above their parent frame in the world coordinates
72+
'''
6373
self.and_srv.wait_for_service()
6474

6575
if not len(names) == len(transforms):
@@ -89,6 +99,7 @@ def get_waypoints(self,frame_type,predicates,transforms,names):
8999
poses = []
90100
for tform in transforms:
91101
poses.append(pm.fromMsg(tform))
102+
break # we only do one
92103

93104
if frame_type not in self.obj_symmetries.keys():
94105
self.obj_symmetries[frame_type] = ObjectSymmetry()
@@ -108,15 +119,6 @@ def get_waypoints(self,frame_type,predicates,transforms,names):
108119
quaternion_list.append(rot_matrix.GetQuaternion())
109120
quaternion_list = np.array(quaternion_list)
110121

111-
unique_rot_matrix = list()
112-
# quaternion_list = np.around(quaternion_list,decimals=5)
113-
# b = np.ascontiguousarray(quaternion_list).view(np.dtype((np.void, quaternion_list.dtype.itemsize * quaternion_list.shape[1])))
114-
# _, unique_indices = np.unique(b, return_index=True)
115-
116-
# for index in unique_indices:
117-
# unique_rot_matrix.append( pm.Rotation.Quaternion( *quaternion_list[index].tolist() ) )
118-
119-
120122
unique_brute_force = list()
121123
for i in xrange(len(quaternion_list)):
122124
unique = True
@@ -126,13 +128,11 @@ def get_waypoints(self,frame_type,predicates,transforms,names):
126128
else:
127129
if abs(quaternion_list[i].dot(quaternion_list[j])) > 0.99:
128130
unique = False
129-
# print i, j, ' is not unique', quaternion_list[i], quaternion_list[j]
130131
break
131132
if unique:
132133
unique_brute_force.append(i)
133-
# print 'unique brute force: ', len(unique_brute_force)
134-
# print unique_brute_force
135134

135+
unique_rot_matrix = list()
136136
for index in unique_brute_force:
137137
unique_rot_matrix.append( pm.Rotation.Quaternion( *quaternion_list[index].tolist() ) )
138138

@@ -142,18 +142,33 @@ def get_waypoints(self,frame_type,predicates,transforms,names):
142142

143143
for match in res.matching:
144144
try:
145-
(trans,rot) = self.listener.lookupTransform(self.world,match,rospy.Time(0))
146-
# for (pose, name) in zip(poses,names):
145+
(trans,rot) = self.listener.lookupTransform(self.world, match, rospy.Time(0))
146+
match_tform = pm.fromTf((trans,rot))
147147

148148
if frame_type in self.obj_symmetries:
149149
for rot_matrix in unique_rot_matrix:
150150
tform = pm.Frame(rot_matrix)
151-
new_poses.append(pm.toMsg(pm.fromTf((trans,rot)) * tform * poses[0]))
151+
world_tform = match_tform * tform * poses[0]
152+
violated = False
153+
for constraint in constraints:
154+
v1 = match_tform.p[constraint.pose_variable]
155+
v2 = world_tform.p[constraint.pose_variable]
156+
if constraint.greater and not (v2 >= v1 + constraint.threshold):
157+
violated = True
158+
#print "VIOLATED", constraint
159+
break
160+
elif not constraint.greater and not (v2 <= v1 - constraint.threshold):
161+
violated = True
162+
#print "VIOLATED", constraint
163+
break
164+
if violated:
165+
continue
166+
#else:
167+
# print match_tform.p, world_tform.p
168+
169+
new_poses.append(pm.toMsg(world_tform))
152170
new_names.append(match + "/" + names[0] + "/x%fy%fz%f"%(rot_matrix.GetRPY()))
153171

154-
#print match, str(match + "/" + names[0] + "/x%fy%fz%f"%(rot_matrix.GetRPY())),
155-
# pm.toTf(pm.fromTf((trans,rot)) * tform * poses[0])[0]
156-
157172
objects.append(match)
158173

159174
except (tf.LookupException, tf.ConnectivityException, tf.ExtrapolationException):

costar_robot/costar_robot_manager/src/costar_robot/costar_arm.py

Lines changed: 14 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -826,7 +826,8 @@ def query(self, req, disable_target_object_collision = False):
826826
req.obj_class, # object class to move to
827827
req.predicates, # predicates to match
828828
[req.pose], # offset/transform from each member of the class
829-
[req.name] # placeholder name
829+
[req.name], # placeholder name
830+
req.constraints,
830831
)
831832

832833
if res is None:
@@ -918,7 +919,18 @@ def query(self, req, disable_target_object_collision = False):
918919

919920
return possible_goals
920921

921-
def smartmove_multipurpose_gripper(self, stamp, possible_goals, distance, gripper_function, velocity, acceleration, backup_in_gripper_frame):
922+
def smartmove_multipurpose_gripper(self,
923+
stamp,
924+
possible_goals,
925+
distance,
926+
gripper_function,
927+
velocity,
928+
acceleration,
929+
backup_in_gripper_frame):
930+
'''
931+
Basic function that handles collecting and aggregating smartmoves
932+
'''
933+
922934
list_of_valid_sequence = list()
923935
list_of_invalid_sequence = list()
924936
self.backoff_waypoints = []

costar_robot/costar_robot_msgs/CMakeLists.txt

Lines changed: 4 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -36,11 +36,10 @@ find_package(catkin REQUIRED std_msgs geometry_msgs predicator_msgs sensor_msgs
3636
## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
3737

3838
## Generate messages in the 'msg' folder
39-
# add_message_files(
40-
# FILES
41-
# Message1.msg
42-
# Message2.msg
43-
# )
39+
add_message_files(
40+
FILES
41+
Constraint.msg
42+
)
4443

4544
## Generate services in the 'srv' folder
4645
add_service_files(
Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,7 @@
1+
int32 pose_variable
2+
float32 threshold
3+
bool greater
4+
5+
int32 POSE_X=0
6+
int32 POSE_Y=1
7+
int32 POSE_Z=2

costar_robot/costar_robot_msgs/srv/SmartMove.srv

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -5,5 +5,10 @@ string name # name of the requested motion
55
float32 accel
66
float32 vel
77
float32 backoff # distance to move back when doing grasp or release
8+
9+
# Restrictions when generating new poses
10+
# --------------------------------------
11+
bool above # new poses should only be created above object goals
12+
costar_robot_msgs/Constraint[] constraints
813
---
914
string ack # what happened

0 commit comments

Comments
 (0)