carl_moveit¶
Contents:
Summary¶
-
carl_moveit
¶
Types¶
Service types¶
-
carl_moveit/CallIK
¶ Field (Request): - pose (geometry_msgs/PoseStamped) –
Field (Response): - jointPositions[] (float64) –
- success (bool) –
geometry_msgs/PoseStamped pose --- float64[] jointPositions bool success
-
carl_moveit/CartesianPath
¶ Field (Request): - waypoints[] (geometry_msgs/Pose) –
- avoidCollisions (bool) –
Field (Response): - success (bool) –
- completion (float64) –
geometry_msgs/Pose[] waypoints # waypoints to plan Cartesian paths through (planning starts from current arm position) bool avoidCollisions # flag to enable/disable collision avoidance --- bool success # true if a path was planned successfully float64 completion # percentage of the path planned
Action types¶
carl_moveit/MoveToJointPose
carl_moveit/WipeSurface
carl_moveit/Pickup
carl_moveit/Arm
carl_moveit/MoveToPose
carl_moveit/Store
-
carl_moveit/MoveToJointPose
¶ Field (Goal): - joints[] (float32) –
- planningTime (float32) –
Field (Result): - success (bool) –
Field (Feedback): - progress (float32) –
float32[] joints # Full set of arm joint angles as a planning goal float32 planningTime # Maximum planning time, defaults to 5 seconds if unset --- bool success # True on successful planning and execution --- float32 progress # Approximate percentage of action complete
-
carl_moveit/WipeSurface
¶ Field (Goal): - height (float64) –
Field (Result): - success (bool) –
Field (Feedback): - message (string) –
float64 height # Height of surface to be wiped --- bool success # True on successful wipe --- string message # The current state message
-
carl_moveit/Pickup
¶ Field (Goal): - pose (geometry_msgs/PoseStamped) –
- lift (bool) –
- verify (bool) –
Field (Result): - success (bool) –
Field (Feedback): - message (string) –
geometry_msgs/PoseStamped pose # End-effector pickup pose bool lift # Flag for arm lifting after pickup bool verify # Flag for grasp verification after gripper close/lift --- bool success # True on successful pickup --- string message # The current state message
-
carl_moveit/Arm
¶ Constant (Goal): - READY (uint8):
0
– - RETRACT (uint8):
1
–
Field (Goal): - action (uint8) –
Field (Result): - success (bool) –
Field (Feedback): - message (string) –
valid actions
# valid actions uint8 READY=0 uint8 RETRACT=1 uint8 action #action that the arm should take --- bool success # True on successful planning and execution --- string message # The current state message
- READY (uint8):
-
carl_moveit/MoveToPose
¶ Field (Goal): - pose (geometry_msgs/PoseStamped) –
- planningTime (float32) –
Field (Result): - success (bool) –
Field (Feedback): - progress (float32) –
geometry_msgs/PoseStamped pose # End-effector pose goal for planning float32 planningTime # Maximum planning time, defaults to 5 seconds if unset --- bool success # True on successful planning and execution --- float32 progress # Approximate percentage of action complete
-
carl_moveit/Store
¶ Field (Goal): - store_pose (geometry_msgs/PoseStamped) –
Field (Result): - success (bool) –
Field (Feedback): - message (string) –
geometry_msgs/PoseStamped store_pose # end-effector pose for storing the held object --- bool success # True on successful store --- string message # The current state message