Skip to content

Commit

Permalink
Expose planning scene to user
Browse files Browse the repository at this point in the history
  • Loading branch information
amalnanavati committed May 6, 2024
1 parent 2bbec1b commit d5ae39e
Showing 1 changed file with 9 additions and 4 deletions.
13 changes: 9 additions & 4 deletions pymoveit2/moveit2.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
JointConstraint,
MoveItErrorCodes,
OrientationConstraint,
PlanningScene,
PositionConstraint,
)
from moveit_msgs.srv import (
Expand Down Expand Up @@ -1801,7 +1802,7 @@ def move_collision(

self.__collision_object_publisher.publish(msg)

def __update_planning_scene(self) -> bool:
def update_planning_scene(self) -> bool:
"""
Gets the current planning scene. Returns whether the service call was
successful.
Expand Down Expand Up @@ -1830,7 +1831,7 @@ def allow_collisions(self, id: str, allow: bool) -> Optional[Future]:
Returns the future of the service call.
"""
# Update the planning scene
if not self.__update_planning_scene():
if not self.update_planning_scene():
return None
allowed_collision_matrix = self.__planning_scene.allowed_collision_matrix
self.__old_allowed_collision_matrix = copy.deepcopy(allowed_collision_matrix)
Expand Down Expand Up @@ -1935,11 +1936,11 @@ def _plan_cartesian_path(
)

# The below attributes were introduced in Iron and do not exist in Humble.
if hasattr(__cartesian_path_request, 'max_velocity_scaling_factor'):
if hasattr(__cartesian_path_request, "max_velocity_scaling_factor"):
self.__cartesian_path_request.max_velocity_scaling_factor = (
self.__move_action_goal.request.max_velocity_scaling_factor
)
if hasattr(__cartesian_path_request, 'max_acceleration_scaling_factor'):
if hasattr(__cartesian_path_request, "max_acceleration_scaling_factor"):
self.__cartesian_path_request.max_acceleration_scaling_factor = (
self.__move_action_goal.request.max_acceleration_scaling_factor
)
Expand Down Expand Up @@ -2206,6 +2207,10 @@ def __init_compute_ik(self):
# self.__compute_ik_req.ik_request.timeout.sec = "Ignored"
# self.__compute_ik_req.ik_request.timeout.nanosec = "Ignored"

@property
def planning_scene(self) -> Optional[PlanningScene]:
return self.__planning_scene

@property
def follow_joint_trajectory_action_client(self) -> str:
return self.__follow_joint_trajectory_action_client
Expand Down

0 comments on commit d5ae39e

Please sign in to comment.