Functions
Planning a path from the start position to the Target (goal) position, and executing that plan.

Functions

void moveit::planning_interface::MoveGroup::allowLooking (bool flag)
 Specify whether the robot is allowed to look around before moving if it determines it should (default is true)
void moveit::planning_interface::MoveGroup::allowReplanning (bool flag)
 Specify whether the robot is allowed to replan if it detects changes in the environment.
bool moveit::planning_interface::MoveGroup::asyncExecute (const Plan &plan)
 Given a plan, execute it without waiting for completion. Return true on success.
bool moveit::planning_interface::MoveGroup::asyncMove ()
 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).
double moveit::planning_interface::MoveGroup::computeCartesianPath (const std::vector< geometry_msgs::Pose > &waypoints, double eef_step, double jump_threshold, moveit_msgs::RobotTrajectory &trajectory, bool avoid_collisions=true)
 Compute a Cartesian path that follows specified waypoints with a step size of at most eef_step meters between end effector configurations of consecutive points in the result trajectory. The reference frame for the waypoints is that specified by setPoseReferenceFrame(). No more than jump_threshold is allowed as change in distance in the configuration space of the robot (this is to prevent 'jumps' in IK solutions). Collisions are avoided if avoid_collisions is set to true. If collisions cannot be avoided, the function fails. Return a value that is between 0.0 and 1.0 indicating the fraction of the path achieved as described by the waypoints. Return -1.0 in case of error.
bool moveit::planning_interface::MoveGroup::execute (const Plan &plan)
 Given a plan, execute it while waiting for completion. Return true on success.
bool moveit::planning_interface::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).
bool moveit::planning_interface::MoveGroup::plan (Plan &plan)
 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.
void moveit::planning_interface::MoveGroup::stop ()
 Stop any trajectory execution, if one is active.

Function Documentation

Specify whether the robot is allowed to look around before moving if it determines it should (default is true)

Definition at line 1423 of file move_group.cpp.

Specify whether the robot is allowed to replan if it detects changes in the environment.

Definition at line 1428 of file move_group.cpp.

Given a plan, execute it without waiting for completion. Return true on success.

Definition at line 886 of file move_group.cpp.

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).

Definition at line 876 of file move_group.cpp.

double moveit::planning_interface::MoveGroup::computeCartesianPath ( const std::vector< geometry_msgs::Pose > &  waypoints,
double  eef_step,
double  jump_threshold,
moveit_msgs::RobotTrajectory &  trajectory,
bool  avoid_collisions = true 
)

Compute a Cartesian path that follows specified waypoints with a step size of at most eef_step meters between end effector configurations of consecutive points in the result trajectory. The reference frame for the waypoints is that specified by setPoseReferenceFrame(). No more than jump_threshold is allowed as change in distance in the configuration space of the robot (this is to prevent 'jumps' in IK solutions). Collisions are avoided if avoid_collisions is set to true. If collisions cannot be avoided, the function fails. Return a value that is between 0.0 and 1.0 indicating the fraction of the path achieved as described by the waypoints. Return -1.0 in case of error.

Definition at line 936 of file move_group.cpp.

Given a plan, execute it while waiting for completion. Return true on success.

Definition at line 891 of file move_group.cpp.

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).

Definition at line 881 of file move_group.cpp.

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.

Definition at line 896 of file move_group.cpp.

Stop any trajectory execution, if one is active.

Definition at line 942 of file move_group.cpp.



planning_interface
Author(s): Ioan Sucan
autogenerated on Mon Oct 6 2014 02:33:28