Skip to content

Commit

Permalink
Allow users to set planner_id and pipeline_id (#48)
Browse files Browse the repository at this point in the history
* Added set_planner_id

* Make planner_id and pipeline_id properties

* Add planner_id param to example files

* Formatting
  • Loading branch information
amalnanavati authored Feb 27, 2024
1 parent 09ce8d8 commit 8bf71ae
Show file tree
Hide file tree
Showing 3 changed files with 28 additions and 2 deletions.
5 changes: 5 additions & 0 deletions examples/ex_joint_goal.py
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,8 @@ def main():
node.declare_parameter("synchronous", True)
# If non-positive, don't cancel. Only used if synchronous is False
node.declare_parameter("cancel_after_secs", 0.0)
# Planner ID
node.declare_parameter("planner_id", "RRTConnectkConfigDefault")

# Create callback group that allows execution of callbacks in parallel without restrictions
callback_group = ReentrantCallbackGroup()
Expand All @@ -51,6 +53,9 @@ def main():
group_name=panda.MOVE_GROUP_ARM,
callback_group=callback_group,
)
moveit2.planner_id = (
node.get_parameter("planner_id").get_parameter_value().string_value
)

# Spin the node in background thread(s) and wait a bit for initialization
executor = rclpy.executors.MultiThreadedExecutor(2)
Expand Down
5 changes: 5 additions & 0 deletions examples/ex_pose_goal.py
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,8 @@ def main():
node.declare_parameter("synchronous", True)
# If non-positive, don't cancel. Only used if synchronous is False
node.declare_parameter("cancel_after_secs", 0.0)
# Planner ID
node.declare_parameter("planner_id", "RRTConnectkConfigDefault")

# Create callback group that allows execution of callbacks in parallel without restrictions
callback_group = ReentrantCallbackGroup()
Expand All @@ -42,6 +44,9 @@ def main():
group_name=panda.MOVE_GROUP_ARM,
callback_group=callback_group,
)
moveit2.planner_id = (
node.get_parameter("planner_id").get_parameter_value().string_value
)

# Spin the node in background thread(s) and wait a bit for initialization
executor = rclpy.executors.MultiThreadedExecutor(2)
Expand Down
20 changes: 18 additions & 2 deletions pymoveit2/moveit2.py
Original file line number Diff line number Diff line change
Expand Up @@ -1933,8 +1933,8 @@ def __init_move_action_goal(
move_action_goal.request.path_constraints = Constraints()
# move_action_goal.request.trajectory_constraints = "Ignored"
# move_action_goal.request.reference_trajectories = "Ignored"
# move_action_goal.request.pipeline_id = "Ignored"
# move_action_goal.request.planner_id = "Ignored"
move_action_goal.request.pipeline_id = ""
move_action_goal.request.planner_id = ""
move_action_goal.request.group_name = group_name
move_action_goal.request.num_planning_attempts = 5
move_action_goal.request.allowed_planning_time = 0.5
Expand Down Expand Up @@ -2056,6 +2056,22 @@ def allowed_planning_time(self) -> float:
def allowed_planning_time(self, value: float):
self.__move_action_goal.request.allowed_planning_time = value

@property
def pipeline_id(self) -> int:
return self.__move_action_goal.request.pipeline_id

@pipeline_id.setter
def pipeline_id(self, value: str):
self.__move_action_goal.request.pipeline_id = value

@property
def planner_id(self) -> int:
return self.__move_action_goal.request.planner_id

@planner_id.setter
def planner_id(self, value: str):
self.__move_action_goal.request.planner_id = value


def init_joint_state(
joint_names: List[str],
Expand Down

0 comments on commit 8bf71ae

Please sign in to comment.