Skip to content

Commit

Permalink
fix doc and action arg type
Browse files Browse the repository at this point in the history
  • Loading branch information
Nikhil-Singhal-06 committed Oct 7, 2024
1 parent afb1d34 commit 37d3483
Show file tree
Hide file tree
Showing 4 changed files with 15 additions and 20 deletions.
19 changes: 11 additions & 8 deletions docs/libraries.rst
Original file line number Diff line number Diff line change
Expand Up @@ -1462,8 +1462,11 @@ Moveit2

The library contains actions to interact with the `Moveit2 <https://moveit.picknik.ai/main/index.html>`__ manipulation stack. Import it with ``import osc.moveit2``. It is provided by the package :repo_link:`libs/scenario_execution_moveit2`.

Actors
^^^^^^

``arm``
^^^^^^^^
^^^^^^^
An articulated arm actor inheriting from the more general ``robot`` actor

.. list-table::
Expand Down Expand Up @@ -1505,9 +1508,9 @@ An articulated arm actor inheriting from the more general ``robot`` actor
- Name of the robot's base link for reference in kinematics

``arm.move_to_joint_pose()``
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
^^^^^^^^^^^^^^^^^^^^^^^^^^^^

Use Moveit2 to move the arm joints to specified joint positions.
Use MoveIt2 to move the arm joints to specified joint positions, utilizing `MoveGroup action <https://docs.ros.org/en/noetic/api/moveit_msgs/html/action/MoveGroup.html>`__ from the move_group node () by specifying target joint values.

.. list-table::
:widths: 15 15 5 65
Expand Down Expand Up @@ -1540,7 +1543,7 @@ Use Moveit2 to move the arm joints to specified joint positions.
- The acceptable range of variation around both the start and goal positions.
* - ``max_velocity_scaling_factor``
- ``float``
- ``false``
- ``0.1``
- Scaling factors for optionally reducing the maximum joint velocities
* - ``namespace_override``
- ``string``
Expand All @@ -1556,16 +1559,16 @@ Use Moveit2 to move the arm joints to specified joint positions.
- Succeed on goal acceptance

``arm.move_to_pose``
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
^^^^^^^^^^^^^^^^^^^^

Use moveit2 to move the end-effector to specified position
Use MoveIt2 to move the end-effector to a specified pose, utilizing `MoveGroup action <https://docs.ros.org/en/noetic/api/moveit_msgs/html/action/MoveGroup.html>`__ from the move_group node by specifying the desired end-effector position and orientation.

* - Parameter
- Type
- Default
- Description
* - ``goal_pose``
- ``list of string``
- ``pose_3d``
-
- end effector pose to move to ``[x, y, z, quatx, quaty, quatz, w]``
* - ``plan_only``
Expand All @@ -1582,7 +1585,7 @@ Use moveit2 to move the end-effector to specified position
- The acceptable range of variation around both the start and goal positions.
* - ``max_velocity_scaling_factor``
- ``float``
- ``false``
- ``0.1``
- Scaling factors for optionally reducing the maximum joint velocities
* - ``namespace_override``
- ``string``
Expand Down
2 changes: 1 addition & 1 deletion examples/example_moveit2/example_moveit2.osc
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ scenario example_moveit2:
goal_pose: ['0.04'],
move_group: move_group_type!gripper)
move_to_pose: manipulator.move_to_pose(
goal_pose: ['0.25', '0.0', '1.0', '0.0', '0.0', '0.0', '1.0'])
goal_pose: pose_3d(position_3d(x: 0.25, y: 0.0, z: 1.0)))
close_gripper: manipulator.move_to_joint_pose(
goal_pose: ['0.01'],
move_group: move_group_type!gripper)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,10 +15,10 @@
# SPDX-License-Identifier: Apache-2.0

from rclpy.duration import Duration
from scenario_execution_ros.actions.common import get_pose_stamped
from scenario_execution_ros.actions.ros_action_call import RosActionCall, ActionCallActionState
from moveit_msgs.action import MoveGroup
from moveit_msgs.msg import MotionPlanRequest, PlanningOptions, Constraints, PositionConstraint, OrientationConstraint, BoundingVolume
from geometry_msgs.msg import PoseStamped
from shape_msgs.msg import SolidPrimitive


Expand Down Expand Up @@ -50,15 +50,7 @@ def get_goal_msg(self):
motion_plan_request.group_name = self.group
motion_plan_request.max_velocity_scaling_factor = self.max_velocity_scaling_factor

target_pose = PoseStamped()
target_pose.header.frame_id = self.base_link # reference_frame
target_pose.pose.position.x = float(self.goal_pose[0])
target_pose.pose.position.y = float(self.goal_pose[1])
target_pose.pose.position.z = float(self.goal_pose[2])
target_pose.pose.orientation.x = float(self.goal_pose[3])
target_pose.pose.orientation.y = float(self.goal_pose[4])
target_pose.pose.orientation.z = float(self.goal_pose[5])
target_pose.pose.orientation.w = float(self.goal_pose[6])
target_pose = get_pose_stamped(self.node.get_clock().now().to_msg(), self.goal_pose)

# Create PositionConstraint
position_constraint = PositionConstraint()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ action arm.move_to_joint_pose:

action arm.move_to_pose:
# Use moveit2 to move the end-effector to specified position
goal_pose: list of string # end effector pose to move to [x, y, z, quatx, quaty, quatz, w]
goal_pose: pose_3d # end effector pose to move to
plan_only: bool = false # if true, the action returns an executable plan in the response but does not attempt execution
replan: bool = true # if true, replan if plan becomes invalidated during execution
tolerance: float = 0.001 # the acceptable range of variation around both the start and goal positions.
Expand Down

0 comments on commit 37d3483

Please sign in to comment.