1414
1515"""BT action leaf nodes for pick-and-place orchestration.
1616
17- Each action wraps one or more PickAndPlaceModule / OSR / GraspGen RPC calls,
17+ Each action wraps one or more BTManipulationModule / OSR / GraspGen RPC calls,
1818following the py_trees lifecycle: initialise() → update() → terminate().
1919
2020Long-running operations (trajectory execution, gripper settle) return RUNNING
@@ -81,11 +81,11 @@ def update(self) -> Status:
8181 time .sleep (self .module .config .prompt_settle_time )
8282
8383 self .module .get_rpc_calls (
84- "PickAndPlaceModule .refresh_obstacles"
84+ "BTManipulationModule .refresh_obstacles"
8585 )(self .min_duration )
8686
8787 detections = self .module .get_rpc_calls (
88- "PickAndPlaceModule .list_cached_detections"
88+ "BTManipulationModule .list_cached_detections"
8989 )() or []
9090
9191 self .bb .detections = detections
@@ -214,7 +214,7 @@ def initialise(self) -> None:
214214 def _run () -> None :
215215 try :
216216 self ._result = self .module .get_rpc_calls (
217- "PickAndPlaceModule .generate_grasps"
217+ "BTManipulationModule .generate_grasps"
218218 )(obj_pc , scene_pc , rpc_timeout = self .rpc_timeout )
219219 except Exception as e :
220220 self ._error = e
@@ -295,7 +295,7 @@ def update(self) -> Status:
295295 if not candidates :
296296 return Status .SUCCESS
297297 try :
298- self .module .get_rpc_calls ("PickAndPlaceModule .visualize_grasps" )(candidates )
298+ self .module .get_rpc_calls ("BTManipulationModule .visualize_grasps" )(candidates )
299299 except Exception as e :
300300 logger .warning (f"[VisualizeGrasps] Visualization failed (non-fatal): { e } " )
301301 return Status .SUCCESS
@@ -441,8 +441,8 @@ def update(self) -> Status:
441441 f"[PlanToPose] Planning to { self .pose_key } "
442442 f"({ pose .position .x :.3f} , { pose .position .y :.3f} , { pose .position .z :.3f} )"
443443 )
444- self .module .get_rpc_calls ("PickAndPlaceModule .reset" )()
445- result = self .module .get_rpc_calls ("PickAndPlaceModule .plan_to_pose" )(pose )
444+ self .module .get_rpc_calls ("BTManipulationModule .reset" )()
445+ result = self .module .get_rpc_calls ("BTManipulationModule .plan_to_pose" )(pose )
446446 if result :
447447 return Status .SUCCESS
448448 self .bb .error_message = f"Error: Planning to { self .pose_key } failed"
@@ -466,8 +466,8 @@ def update(self) -> Status:
466466 if isinstance (joints , list ):
467467 joints = JointState (position = joints )
468468 logger .info (f"[PlanToJoints] Planning to { self .joints_key } " )
469- self .module .get_rpc_calls ("PickAndPlaceModule .reset" )()
470- result = self .module .get_rpc_calls ("PickAndPlaceModule .plan_to_joints" )(joints )
469+ self .module .get_rpc_calls ("BTManipulationModule .reset" )()
470+ result = self .module .get_rpc_calls ("BTManipulationModule .plan_to_joints" )(joints )
471471 if result :
472472 return Status .SUCCESS
473473 self .bb .error_message = f"Error: Joint planning to { self .joints_key } failed"
@@ -495,7 +495,7 @@ def __init__(
495495 def initialise (self ) -> None :
496496 self ._seen_executing = False
497497 try :
498- result = self .module .get_rpc_calls ("PickAndPlaceModule .execute" )()
498+ result = self .module .get_rpc_calls ("BTManipulationModule .execute" )()
499499 self ._execute_ok = bool (result )
500500 except Exception as e :
501501 logger .error (f"[ExecuteTrajectory] Execute call failed: { e } " )
@@ -508,7 +508,7 @@ def update(self) -> Status:
508508 return Status .FAILURE
509509
510510 try :
511- status = self .module .get_rpc_calls ("PickAndPlaceModule .get_trajectory_status" )()
511+ status = self .module .get_rpc_calls ("BTManipulationModule .get_trajectory_status" )()
512512 except Exception as e :
513513 logger .warning (f"[ExecuteTrajectory] Status poll failed: { e } " )
514514 status = None
@@ -541,7 +541,7 @@ def update(self) -> Status:
541541 def terminate (self , new_status : Status ) -> None :
542542 if new_status == Status .INVALID :
543543 try :
544- self .module .get_rpc_calls ("PickAndPlaceModule .cancel" )()
544+ self .module .get_rpc_calls ("BTManipulationModule .cancel" )()
545545 logger .info ("[ExecuteTrajectory] Cancelled trajectory on interrupt" )
546546 except Exception as e :
547547 logger .warning (f"[ExecuteTrajectory] Cancel on interrupt failed (best-effort): { e } " )
@@ -566,7 +566,7 @@ def __init__(
566566
567567 def initialise (self ) -> None :
568568 try :
569- self .module .get_rpc_calls ("PickAndPlaceModule .set_gripper" )(self .position )
569+ self .module .get_rpc_calls ("BTManipulationModule .set_gripper" )(self .position )
570570 self ._command_sent = True
571571 except Exception as e :
572572 logger .error (f"[SetGripper] Command failed: { e } " )
@@ -641,11 +641,11 @@ def update(self) -> Status:
641641# --- Robot state actions ---
642642
643643class ResetRobot (ManipulationAction ):
644- """Call PickAndPlaceModule .reset() to clear fault/abort state."""
644+ """Call BTManipulationModule .reset() to clear fault/abort state."""
645645
646646 def update (self ) -> Status :
647647 try :
648- result = self .module .get_rpc_calls ("PickAndPlaceModule .reset" )()
648+ result = self .module .get_rpc_calls ("BTManipulationModule .reset" )()
649649 if result :
650650 logger .info ("[ResetRobot] Reset succeeded" )
651651 return Status .SUCCESS
@@ -675,7 +675,7 @@ def initialise(self) -> None:
675675 def update (self ) -> Status :
676676 if not self ._cancel_sent :
677677 try :
678- self .module .get_rpc_calls ("PickAndPlaceModule .cancel" )()
678+ self .module .get_rpc_calls ("BTManipulationModule .cancel" )()
679679 logger .info ("[CancelMotion] Cancel sent, waiting for settle" )
680680 except Exception as e :
681681 logger .warning (f"[CancelMotion] Cancel failed (best-effort): { e } " )
@@ -734,7 +734,7 @@ def __init__(self, name: str, module: PickPlaceModule) -> None:
734734
735735 def update (self ) -> Status :
736736 try :
737- pos = float (self .module .get_rpc_calls ("PickAndPlaceModule .get_gripper" )())
737+ pos = float (self .module .get_rpc_calls ("BTManipulationModule .get_gripper" )())
738738 threshold = self .module .config .gripper_grasp_threshold
739739 open_pos = self .module .config .gripper_open_position
740740 # Upper bound at 90% of open prevents false positive when gripper is wide open
@@ -778,7 +778,7 @@ def update(self) -> Status:
778778 lift_h = self ._lift_height if self ._lift_height is not None else self .module .config .lift_height
779779
780780 try :
781- base_pose = self .module .get_rpc_calls ("PickAndPlaceModule .get_ee_pose" )()
781+ base_pose = self .module .get_rpc_calls ("BTManipulationModule .get_ee_pose" )()
782782 except Exception as e :
783783 logger .warning (f"[ComputeLiftPose] get_ee_pose failed, falling back to current_grasp: { e } " )
784784 base_pose = None
@@ -811,7 +811,7 @@ def update(self) -> Status:
811811 height = self ._retreat_height if self ._retreat_height is not None else self .module .config .lift_height
812812
813813 try :
814- base_pose = self .module .get_rpc_calls ("PickAndPlaceModule .get_ee_pose" )()
814+ base_pose = self .module .get_rpc_calls ("BTManipulationModule .get_ee_pose" )()
815815 except Exception as e :
816816 logger .warning (f"[ComputeLocalRetreatPose] get_ee_pose failed: { e } " )
817817 base_pose = None
0 commit comments