3333from compas_fab .backends .ros .messages import PositionConstraint
3434from compas_fab .backends .ros .messages import PositionIKRequest
3535from compas_fab .backends .ros .messages import RobotState
36+ from compas_fab .backends .ros .messages import TrajectoryConstraints
3637from compas_fab .backends .ros .planner_backend import PlannerBackend
3738from compas_fab .backends .ros .planner_backend import ServiceDescription
3839from compas_fab .robots import Configuration
@@ -113,6 +114,27 @@ def dispose_planner(self):
113114 if hasattr (self , 'attached_collision_object_topic' ) and self .attached_collision_object_topic :
114115 self .attached_collision_object_topic .unadvertise ()
115116
117+ def _convert_constraints_to_rosmsg (self , constraints , header ):
118+ """Convert COMPAS FAB constraints into ROS Messages."""
119+ if not constraints :
120+ return None
121+
122+ ros_constraints = Constraints ()
123+ for c in constraints :
124+ if c .type == c .JOINT :
125+ ros_constraints .joint_constraints .append (
126+ JointConstraint .from_joint_constraint (c ))
127+ elif c .type == c .POSITION :
128+ ros_constraints .position_constraints .append (
129+ PositionConstraint .from_position_constraint (header , c ))
130+ elif c .type == c .ORIENTATION :
131+ ros_constraints .orientation_constraints .append (
132+ OrientationConstraint .from_orientation_constraint (header , c ))
133+ else :
134+ raise NotImplementedError
135+
136+ return ros_constraints
137+
116138 # ==========================================================================
117139 # planning services
118140 # ==========================================================================
@@ -134,6 +156,8 @@ def inverse_kinematics_async(self, callback, errback, robot, frame, group,
134156 aco = AttachedCollisionObject .from_attached_collision_mesh (acm )
135157 start_state .attached_collision_objects .append (aco )
136158
159+ constraints = self ._convert_constraints_to_rosmsg (constraints , header )
160+
137161 ik_request = PositionIKRequest (group_name = group ,
138162 robot_state = start_state ,
139163 constraints = constraints ,
@@ -184,6 +208,8 @@ def plan_cartesian_motion_async(self, callback, errback,
184208 aco = AttachedCollisionObject .from_attached_collision_mesh (acm )
185209 start_state .attached_collision_objects .append (aco )
186210
211+ path_constraints = self ._convert_constraints_to_rosmsg (path_constraints , header )
212+
187213 request = dict (header = header ,
188214 start_state = start_state ,
189215 group_name = group ,
@@ -243,38 +269,12 @@ def plan_motion_async(self, callback, errback,
243269 aco = AttachedCollisionObject .from_attached_collision_mesh (acm )
244270 start_state .attached_collision_objects .append (aco )
245271
246- # goal constraints
247- constraints = Constraints ()
248- for c in goal_constraints :
249- if c .type == c .JOINT :
250- constraints .joint_constraints .append (
251- JointConstraint .from_joint_constraint (c ))
252- elif c .type == c .POSITION :
253- constraints .position_constraints .append (
254- PositionConstraint .from_position_constraint (header , c ))
255- elif c .type == c .ORIENTATION :
256- constraints .orientation_constraints .append (
257- OrientationConstraint .from_orientation_constraint (header , c ))
258- else :
259- raise NotImplementedError
260- goal_constraints = [constraints ]
261-
262- # path constraints
263- if path_constraints :
264- constraints = Constraints ()
265- for c in path_constraints :
266- if c .type == c .JOINT :
267- constraints .joint_constraints .append (
268- JointConstraint .from_joint_constraint (c ))
269- elif c .type == c .POSITION :
270- constraints .position_constraints .append (
271- PositionConstraint .from_position_constraint (header , c ))
272- elif c .type == c .ORIENTATION :
273- constraints .orientation_constraints .append (
274- OrientationConstraint .from_orientation_constraint (header , c ))
275- else :
276- raise NotImplementedError
277- path_constraints = constraints
272+ # convert constraints
273+ goal_constraints = [self ._convert_constraints_to_rosmsg (goal_constraints , header )]
274+ path_constraints = self ._convert_constraints_to_rosmsg (path_constraints , header )
275+
276+ if trajectory_constraints is not None :
277+ trajectory_constraints = TrajectoryConstraints (constraints = self ._convert_constraints_to_rosmsg (path_constraints , header ))
278278
279279 request = dict (start_state = start_state ,
280280 goal_constraints = goal_constraints ,
0 commit comments