"""
Example of moving to a pose goal.
- ros2 run pymoveit2 ex_pose_goal.py --ros-args -p position:="[0.25, 0.0, 1.0]" -p quat_xyzw:="[0.0, 0.0, 0.0, 1.0]" -p cartesian:=False
- ros2 run pymoveit2 ex_pose_goal.py --ros-args -p position:="[0.25, 0.0, 1.0]" -p quat_xyzw:="[0.0, 0.0, 0.0, 1.0]" -p cartesian:=False -p synchronous:=False -p cancel_after_secs:=1.0
- ros2 run pymoveit2 ex_pose_goal.py --ros-args -p position:="[0.25, 0.0, 1.0]" -p quat_xyzw:="[0.0, 0.0, 0.0, 1.0]" -p cartesian:=False -p synchronous:=False -p cancel_after_secs:=0.0
"""
from threading import Thread
import rclpy
from rclpy.callback_groups import ReentrantCallbackGroup
from rclpy.node import Node
from pymoveit2 import MoveIt2, MoveIt2State
from pymoveit2.robots import panda as robot
def main():
rclpy.init()
node = Node("ex_pose_goal")
node.declare_parameter("position", [0.5, 0.0, 0.25])
node.declare_parameter("quat_xyzw", [1.0, 0.0, 0.0, 0.0])
node.declare_parameter("synchronous", True)
node.declare_parameter("cancel_after_secs", 0.0)
node.declare_parameter("planner_id", "RRTConnectkConfigDefault")
node.declare_parameter("cartesian", False)
node.declare_parameter("cartesian_max_step", 0.0025)
node.declare_parameter("cartesian_fraction_threshold", 0.0)
node.declare_parameter("cartesian_jump_threshold", 0.0)
node.declare_parameter("cartesian_avoid_collisions", False)
callback_group = ReentrantCallbackGroup()
moveit2 = MoveIt2(
node=node,
joint_names=robot.joint_names(),
base_link_name=robot.base_link_name(),
end_effector_name=robot.end_effector_name(),
group_name=robot.MOVE_GROUP_ARM,
callback_group=callback_group,
)
moveit2.planner_id = (
node.get_parameter("planner_id").get_parameter_value().string_value
)
executor = rclpy.executors.MultiThreadedExecutor(2)
executor.add_node(node)
executor_thread = Thread(target=executor.spin, daemon=True, args=())
executor_thread.start()
node.create_rate(1.0).sleep()
moveit2.max_velocity = 0.5
moveit2.max_acceleration = 0.5
position = node.get_parameter("position").get_parameter_value().double_array_value
quat_xyzw = node.get_parameter("quat_xyzw").get_parameter_value().double_array_value
synchronous = node.get_parameter("synchronous").get_parameter_value().bool_value
cancel_after_secs = (
node.get_parameter("cancel_after_secs").get_parameter_value().double_value
)
cartesian = node.get_parameter("cartesian").get_parameter_value().bool_value
cartesian_max_step = (
node.get_parameter("cartesian_max_step").get_parameter_value().double_value
)
cartesian_fraction_threshold = (
node.get_parameter("cartesian_fraction_threshold")
.get_parameter_value()
.double_value
)
cartesian_jump_threshold = (
node.get_parameter("cartesian_jump_threshold")
.get_parameter_value()
.double_value
)
cartesian_avoid_collisions = (
node.get_parameter("cartesian_avoid_collisions")
.get_parameter_value()
.bool_value
)
moveit2.cartesian_avoid_collisions = cartesian_avoid_collisions
moveit2.cartesian_jump_threshold = cartesian_jump_threshold
node.get_logger().info(
f"Moving to {{position: {list(position)}, quat_xyzw: {list(quat_xyzw)}}}"
)
moveit2.move_to_pose(
position=position,
quat_xyzw=quat_xyzw,
cartesian=cartesian,
cartesian_max_step=cartesian_max_step,
cartesian_fraction_threshold=cartesian_fraction_threshold,
)
if synchronous:
moveit2.wait_until_executed()
else:
print("Current State: " + str(moveit2.query_state()))
rate = node.create_rate(10)
while moveit2.query_state() != MoveIt2State.EXECUTING:
rate.sleep()
print("Current State: " + str(moveit2.query_state()))
future = moveit2.get_execution_future()
if cancel_after_secs > 0.0:
sleep_time = node.create_rate(cancel_after_secs)
sleep_time.sleep()
print("Cancelling goal")
moveit2.cancel_execution()
while not future.done():
rate.sleep()
print("Result status: " + str(future.result().status))
print("Result error code: " + str(future.result().result.error_code))
rclpy.shutdown()
executor_thread.join()
exit(0)
if __name__ == "__main__":
main()