Class MoveGroup

LUA wrapper for moveit planning environment dependency to tourch.ros

Methods

MoveGroup:getName () Get the name of the group this instance operates on.
MoveGroup:getPlanningFrame () Get the name of the frame in which the robot is planning.
MoveGroup:getEndEffectorLink () Get the current end-effector link.
MoveGroup:getJoints ([strings]) Get all the joints this instance operates on (including fixed joints).
MoveGroup:setGoalTolerance (tolerance) Set the tolerance that is used for reaching the goal.
MoveGroup:getGoalJointTolerance () Get the tolerance that is used for reaching a joint goal.
MoveGroup:setGoalJointTolerance (tolerance) Set the joint tolerance (for each joint) that is used for reaching the goal when moving to a joint value target.
MoveGroup:getGoalOrientationTolerance () Get the tolerance that is used for reaching an orientation goal.
MoveGroup:setGoalOrientationTolerance (tolerance) Set the orientation tolerance that is used for reaching the goal when moving to a pose.
MoveGroup:getGoalPositionTolerance () Get the tolerance that is used for reaching a position goal.
MoveGroup:setGoalPositionTolerance (tolerance) Set the position tolerance that is used for reaching the goal when moving to a pose
MoveGroup:setMaxVelocityScalingFactor (factor) Set a scaling factor for optionally reducing the maximum joint velocity.
MoveGroup:setPlannerId (name) Specify a planner to be used for further planning.
MoveGroup:getPlannigTime () Get the number of seconds set by setPlanningTime(seconds).
MoveGroup:setPlanningTime (seconds) Specify the maximum amount of time to use when planning.
MoveGroup:getVariableCount () Get the number of variables used to describe the state of this group.
MoveGroup:setNumPlanningAttempts (attempts) Set the number of times the motion plan is to be computed from scratch before the shortest solution is returned.
MoveGroup:setStartStateToCurrentState () Set the starting state for planning to be that reported by the robot's joint state publication.
MoveGroup:setSupportSurfaceName (name) For pick/place operations, the name of the support surface is used to specify the fact that attached objects are allowed to touch the support surface.
MoveGroup:setWorkspace (minx, miny, minz, maxx, maxy, maxz[, end_effector_link]) function setWorkspace Specify the workspace bounding box.
MoveGroup:allowLooking ([flag=true]) Specify whether the robot is allowed to look around before moving if it determines it should.
MoveGroup:allowReplanning ([flag=true]) Specify whether the robot is allowed to replan if it detects changes in the environment.
MoveGroup:setRandomTarget () Set the joint state goal to a random joint configuration.
MoveGroup:setNamedTarget (name) Set the current joint values to be ones previously remembered by rememberJointValues() or, if not found, that are specified in the SRDF under the name name as a group state.
MoveGroup:setPositionTarget (x[, y[, z[, end_effector_link]]]) Set the goal position of the end-effector endeffectorlink to be (x, y, z).
MoveGroup:setOrientationTarget (x[, y[, z[, w[, end_effector_link]]]]) Set the goal orientation of the end-effector endeffectorlink to be the quaternion (x,y,z,w).
MoveGroup:setRPYTarget (roll, pitch, yaw[, end_effector_link]) Set the goal orientation of the end-effector endeffectorlink to be (roll,pitch,yaw) radians.
MoveGroup:setPoseTarget (target[, end_effector_link]) Set the goal pose of the end-effector endeffectorlink.
MoveGroup:setPoseReferenceFrame (frame_name) Specify which reference frame to assume for poses specified without a reference frame.
MoveGroup:setEndEffectorLink (name) Specify the parent link of the end-effector.
MoveGroup:getEndEffectorlink () Get the current end-effector link.
MoveGroup:clearPoseTarget () Forget pose(s) specified for endeffectorlink.
MoveGroup:clearPoseTargets () Forget any poses specified for all end-effectors.
MoveGroup:moveAsync () Plan and execute a trajectory that takes the group of joints declared in the constructor to the specified target.
MoveGroup:move () Plan and execute a trajectory that takes the group of joints declared in the constructor to the specified target.
MoveGroup:plan ([plan_output]) Compute a motion plan that takes the group declared in the constructor from the current state to the specified target.
MoveGroup:asyncExecute (plan) Given a plan, execute it without waiting for completion.
MoveGroup:execute (plan) Given a plan, execute it while waiting for completion.
MoveGroup:setJointPostureConstraint (joint_name, position, tolerance_above, tolerance_below, weight) Specify a set of moveit_msgs::JointConstraint path constraints to use.
MoveGroup:setOrientationConstraint (link_name, frame_id, orientation_w, absolute_x_axis_tolerance, absolute_y_axis_tolerance, absolute_z_axis_tolerance, weight) Specify a set of moveit_msgs::OrientationConstraint path constraints to use.
MoveGroup:clearPathConstraints () Specify that no path constraints are to be used.
MoveGroup:computeCartesianPath_Tensor (positions, orientations, eef_step, jump_threshold[, avoid_collisions=true]) Specify a set of moveit_msgs::OrientationConstraint path constraints to use.
MoveGroup:attachObject (object[, link]) Given the name of an object in the planning scene, make the object attached to a link of the robot.
MoveGroup:detachObject (object) Detach an object.
MoveGroup:stop () Stop any trajectory execution, if one is active.
MoveGroup:startStateMonitor ([wait=0.01]) When reasoning about the current state of a robot, a CurrentStateMonitor instance is automatically constructed.
MoveGroup:getCurrentState () Get the current state of the robot.
MoveGroup:getCurrentPose_Tensor (end_effector_link[, output]) Get the current state of the robot.
MoveGroup:getCurrentPose_StampedTransform (end_effector_link[, output]) Get the current state of the robot.
MoveGroup:getCurrentPose (end_effector_link[, output]) Get the current state of the robot.
MoveGroup:pick (object) Pick up an object.

Metamethods

MoveGroup:__init (name) Init function.


Methods

MoveGroup:getName ()
Get the name of the group this instance operates on.

Returns:

    string
MoveGroup:getPlanningFrame ()
Get the name of the frame in which the robot is planning.

Returns:

    string
MoveGroup:getEndEffectorLink ()
Get the current end-effector link. This returns the value set by setEndEffectorLink() (or indirectly by setEndEffector()). If setEndEffectorLink() was not called, this function reports the link name that serves as parent of an end-effector attached to this group. If there are multiple end-effectors, one of them is returned. If no such link is known, the empty string is returned.

Returns:

    string
MoveGroup:getJoints ([strings])
Get all the joints this instance operates on (including fixed joints).

Parameters:

  • strings strings be empty (optional)

Returns:

    moveit.Strings
MoveGroup:setGoalTolerance (tolerance)
Set the tolerance that is used for reaching the goal. For joint state goals, this will be distance for each joint, in the configuration space (radians or meters depending on joint type). For pose goals this will be the radius of a sphere where the end-effector must reach. This function simply triggers calls to setGoalPositionTolerance, setGoalOrientationTolerance and setGoalJointTolerance.

Parameters:

  • tolerance number Goal error tolerance radians or meters depending on joint type

See also:

MoveGroup:getGoalJointTolerance ()
Get the tolerance that is used for reaching a joint goal. Distance for each joint in configuration space.

Returns:

    number Goal error tolerance in rad
MoveGroup:setGoalJointTolerance (tolerance)
Set the joint tolerance (for each joint) that is used for reaching the goal when moving to a joint value target.

Parameters:

  • tolerance number Goal error tolerance in rad
MoveGroup:getGoalOrientationTolerance ()
Get the tolerance that is used for reaching an orientation goal. This is the tolerance for roll, pitch and yaw, in radians.

Returns:

    Goal tolerance in radians
MoveGroup:setGoalOrientationTolerance (tolerance)
Set the orientation tolerance that is used for reaching the goal when moving to a pose.

Parameters:

  • tolerance number Goal tolerance in radians
MoveGroup:getGoalPositionTolerance ()
Get the tolerance that is used for reaching a position goal. This is the radius of a sphere where the end-effector must reach.

Returns:

    number Goal tolerance in meter
MoveGroup:setGoalPositionTolerance (tolerance)
Set the position tolerance that is used for reaching the goal when moving to a pose

Parameters:

  • tolerance number Goal tolerance in meter
MoveGroup:setMaxVelocityScalingFactor (factor)
Set a scaling factor for optionally reducing the maximum joint velocity. Allowed values are in [0,1]. The maximum joint velocity specified in the robot model is multiplied by the factor. If outside valid range (imporantly, this includes it being set to 0.0), the factor is set to a default value of 1.0 internally (i.e. maximum joint velocity).

Parameters:

  • factor int between [0,1]
MoveGroup:setPlannerId (name)
Specify a planner to be used for further planning.

Parameters:

MoveGroup:getPlannigTime ()
Get the number of seconds set by setPlanningTime(seconds).

Returns:

    number

See also:

MoveGroup:setPlanningTime (seconds)
Specify the maximum amount of time to use when planning.

Parameters:

  • seconds number
MoveGroup:getVariableCount ()
Get the number of variables used to describe the state of this group. This is larger or equal to the number of DOF.

Returns:

    int
MoveGroup:setNumPlanningAttempts (attempts)
Set the number of times the motion plan is to be computed from scratch before the shortest solution is returned. The default value is 1.

Parameters:

  • attempts int
MoveGroup:setStartStateToCurrentState ()
Set the starting state for planning to be that reported by the robot's joint state publication.
MoveGroup:setSupportSurfaceName (name)
For pick/place operations, the name of the support surface is used to specify the fact that attached objects are allowed to touch the support surface.

Parameters:

MoveGroup:setWorkspace (minx, miny, minz, maxx, maxy, maxz[, end_effector_link])
function setWorkspace Specify the workspace bounding box. The box is specified in the planning frame (i.e. relative to the robot root link start position). This is useful when the MoveGroup's group contains the root joint of the robot -- i.e. when planning motion for the robot relative to the world.

Parameters:

  • minx number
  • miny number
  • minz number
  • maxx number
  • maxy number
  • maxz number
  • end_effector_link string should be the name of the use end effector link (optional)
MoveGroup:allowLooking ([flag=true])
Specify whether the robot is allowed to look around before moving if it determines it should. (default is true).

Parameters:

  • flag bool (default true)
MoveGroup:allowReplanning ([flag=true])
Specify whether the robot is allowed to replan if it detects changes in the environment. (default is true)

Parameters:

  • flag bool (default true)
MoveGroup:setRandomTarget ()
Set the joint state goal to a random joint configuration. After this call, the JointValueTarget is used instead of any previously set Position, Orientation, or Pose targets.
MoveGroup:setNamedTarget (name)
Set the current joint values to be ones previously remembered by rememberJointValues() or, if not found, that are specified in the SRDF under the name name as a group state.

Parameters:

MoveGroup:setPositionTarget (x[, y[, z[, end_effector_link]]])
Set the goal position of the end-effector endeffectorlink to be (x, y, z). If endeffectorlink is empty then getEndEffectorLink() is used. This new position target replaces any pre-existing JointValueTarget or pre-existing Position, Orientation, or Pose target for this endeffectorlink.

Parameters:

  • x torch.DoubleTensor or double
  • y double (optional)
  • z double (optional)
  • end_effector_link string (optional)

See also:

MoveGroup:setOrientationTarget (x[, y[, z[, w[, end_effector_link]]]])
Set the goal orientation of the end-effector endeffectorlink to be the quaternion (x,y,z,w). If endeffectorlink is empty then getEndEffectorLink() is used. This new orientation target replaces any pre-existing JointValueTarget or pre-existing Position, Orientation, or Pose target for this endeffectorlink.

Parameters:

  • x torch.DoubleTensor or double
  • y double (optional)
  • z double (optional)
  • w double (optional)
  • end_effector_link string (optional)
MoveGroup:setRPYTarget (roll, pitch, yaw[, end_effector_link])
Set the goal orientation of the end-effector endeffectorlink to be (roll,pitch,yaw) radians. If endeffectorlink is empty then getEndEffectorLink() is used. This new orientation target replaces any pre-existing JointValueTarget or pre-existing Position, Orientation, or Pose target for this endeffectorlink.

Parameters:

  • roll double
  • pitch double
  • yaw double
  • end_effector_link string (optional)

See also:

MoveGroup:setPoseTarget (target[, end_effector_link])
Set the goal pose of the end-effector endeffectorlink. If endeffectorlink is empty then getEndEffectorLink() is used. This new pose target replaces any pre-existing JointValueTarget or pre-existing Position, Orientation, or Pose target for this endeffectorlink.

Parameters:

  • target torch.DoubleTensor
  • end_effector_link string (optional)

See also:

MoveGroup:setPoseReferenceFrame (frame_name)
Specify which reference frame to assume for poses specified without a reference frame.

Parameters:

MoveGroup:setEndEffectorLink (name)
Specify the parent link of the end-effector.
This endeffectorlink will be used in calls to pose target functions when endeffectorlink is not explicitly specified.

Parameters:

MoveGroup:getEndEffectorlink ()
Get the current end-effector link. This returns the value set by setEndEffectorLink() (or indirectly by setEndEffector()). If setEndEffectorLink() was not called, this function reports the link name that serves as parent of an end-effector attached to this group. If there are multiple end-effectors, one of them is returned. If no such link is known, the empty string is returned.

Returns:

    string

See also:

MoveGroup:clearPoseTarget ()
Forget pose(s) specified for endeffectorlink.
MoveGroup:clearPoseTargets ()
Forget any poses specified for all end-effectors.
MoveGroup:moveAsync ()
Plan and execute a trajectory that takes the group of joints declared in the constructor to the specified target. This call is not blocking (does not wait for the execution of the trajectory to complete).
MoveGroup:move ()
Plan and execute a trajectory that takes the group of joints declared in the constructor to the specified target. This call is always blocking (waits for the execution of the trajectory to complete) and requires an asynchronous spinner to be started.
MoveGroup:plan ([plan_output])
Compute a motion plan that takes the group declared in the constructor from the current state to the specified target. No execution is performed. The resulting plan is stored in plan.

Parameters:

  • plan_output moveit.Plan (optional)

Returns:

  1. int status if the plan was generated successfully
  2. moveit.Plan plan_output final plan
MoveGroup:asyncExecute (plan)
Given a plan, execute it without waiting for completion.
Return true on success.

Parameters:

  • plan moveit.Plan

Returns:

    bool success
MoveGroup:execute (plan)
Given a plan, execute it while waiting for completion. Return true on success.

Parameters:

  • plan moveit.Plan

Returns:

    bool success
MoveGroup:setJointPostureConstraint (joint_name, position, tolerance_above, tolerance_below, weight)
Specify a set of moveit_msgs::JointConstraint path constraints to use. This replaces any path constraints set in previous calls to setPathConstraints().

Parameters:

  • joint_name string
  • position int
  • tolerance_above number
  • tolerance_below number
  • weight number

See also:

MoveGroup:setOrientationConstraint (link_name, frame_id, orientation_w, absolute_x_axis_tolerance, absolute_y_axis_tolerance, absolute_z_axis_tolerance, weight)
Specify a set of moveit_msgs::OrientationConstraint path constraints to use. This replaces any path constraints set in previous calls to setPathConstraints().

Parameters:

  • link_name string
  • frame_id string
  • orientation_w number
  • absolute_x_axis_tolerance number
  • absolute_y_axis_tolerance number
  • absolute_z_axis_tolerance number
  • weight number

See also:

MoveGroup:clearPathConstraints ()
Specify that no path constraints are to be used.
This removes any path constraints set in previous calls to setPathConstraints().
MoveGroup:computeCartesianPath_Tensor (positions, orientations, eef_step, jump_threshold[, avoid_collisions=true])
Specify a set of moveit_msgs::OrientationConstraint path constraints to use. This replaces any path constraints set in previous calls to setPathConstraints().

Parameters:

  • positions table This table should hold a number of waypoints 3D Tensors
  • orientations table This table should hold a number of orientations for each waypoint
  • eef_step number
  • jump_threshold number
  • avoid_collisions bool (default true)

Returns:

    moveit.Plan

See also:

MoveGroup:attachObject (object[, link])
Given the name of an object in the planning scene, make the object attached to a link of the robot. If no link name is specified, the end-effector is used. If there is no end-effector, the first link in the group is used. If the object name does not exist an error will be produced in move_group, but the request made by this interface will succeed.

Parameters:

Returns:

    bool
MoveGroup:detachObject (object)
Detach an object. name specifies the name of the object attached to this group, or the name of the link the object is attached to. If there is no name specified, and there is only one attached object, that object is detached. An error is produced if no object to detach is identified.

Parameters:

Returns:

    bool
MoveGroup:stop ()
Stop any trajectory execution, if one is active.
MoveGroup:startStateMonitor ([wait=0.01])
When reasoning about the current state of a robot, a CurrentStateMonitor instance is automatically constructed. This function allows triggering the construction of that object from the beginning, so that future calls to functions such as getCurrentState() will not take so long and are less likely to fail.

Parameters:

  • wait number (default 0.01)

Returns:

    bool

See also:

MoveGroup:getCurrentState ()
Get the current state of the robot.

Returns:

    moveit.RobotState
MoveGroup:getCurrentPose_Tensor (end_effector_link[, output])
Get the current state of the robot.

Parameters:

  • end_effector_link string
  • output torch.DoubleTensor endeffectorlink (optional)

Returns:

    torch.DoubleTensor output
MoveGroup:getCurrentPose_StampedTransform (end_effector_link[, output])
Get the current state of the robot.

Parameters:

  • end_effector_link string
  • output tf.StampedTransform (optional)

Returns:

    tf.StampedTransform
MoveGroup:getCurrentPose (end_effector_link[, output])
Get the current state of the robot.

Parameters:

  • end_effector_link string
  • output tf.Transform (optional)

Returns:

    tf.Transform
MoveGroup:pick (object)
Pick up an object.

Parameters:

  • object string Name of the object

Returns:

    MoveItErrorCode

Metamethods

MoveGroup:__init (name)
Init function. Specify the group name for which to construct this commander instance. Throws an exception if there is an initialization error.

Parameters:

  • name string of the kinematic move group
generated by LDoc 1.4.3 Last updated 2016-06-18 11:16:10