Functions
Setting a joint state target (goal)

Functions

const
robot_state::JointStateGroup
moveit::planning_interface::MoveGroup::getJointValueTarget () const
 Get the currently set joint state goal.
bool moveit::planning_interface::MoveGroup::setJointValueTarget (const std::vector< double > &group_variable_values)
 Given a vector of real values in the same order as expected by the group, set those as the joint state goal.
bool moveit::planning_interface::MoveGroup::setJointValueTarget (const std::map< std::string, double > &variable_values)
 Given a map of joint names to real values, set those as the joint state goal.
bool moveit::planning_interface::MoveGroup::setJointValueTarget (const robot_state::RobotState &robot_state)
 Set the joint state goal from corresponding joint values from the specified state. Values from state for joints not in this MoveGroup's group are ignored.
bool moveit::planning_interface::MoveGroup::setJointValueTarget (const robot_state::JointStateGroup &joint_state_group)
 Set the joint state goal from corresponding joint values from the specified group. joint_state_group must represent the same group as this MoveGroup.
bool moveit::planning_interface::MoveGroup::setJointValueTarget (const robot_state::JointState &joint_state)
 Set the joint state goal for a particular joint.
bool moveit::planning_interface::MoveGroup::setJointValueTarget (const std::string &joint_name, const std::vector< double > &values)
 Set the joint state goal for a particular joint.
bool moveit::planning_interface::MoveGroup::setJointValueTarget (const std::string &joint_name, double value)
 Set the joint state goal for a particular joint.
bool moveit::planning_interface::MoveGroup::setJointValueTarget (const sensor_msgs::JointState &state)
 Set the joint state goal for a particular joint.
bool moveit::planning_interface::MoveGroup::setNamedTarget (const std::string &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.
void moveit::planning_interface::MoveGroup::setRandomTarget ()
 Set the joint state goal to a random joint configuration.

Function Documentation

Get the currently set joint state goal.

Definition at line 1037 of file move_group.cpp.

bool moveit::planning_interface::MoveGroup::setJointValueTarget ( const std::vector< double > &  group_variable_values)

Given a vector of real values in the same order as expected by the group, set those as the joint state goal.

Definition at line 981 of file move_group.cpp.

bool moveit::planning_interface::MoveGroup::setJointValueTarget ( const std::map< std::string, double > &  variable_values)

Given a map of joint names to real values, set those as the joint state goal.

Definition at line 990 of file move_group.cpp.

Set the joint state goal from corresponding joint values from the specified state. Values from state for joints not in this MoveGroup's group are ignored.

Definition at line 997 of file move_group.cpp.

Set the joint state goal from corresponding joint values from the specified group. joint_state_group must represent the same group as this MoveGroup.

Definition at line 1002 of file move_group.cpp.

Set the joint state goal for a particular joint.

Definition at line 1009 of file move_group.cpp.

bool moveit::planning_interface::MoveGroup::setJointValueTarget ( const std::string &  joint_name,
const std::vector< double > &  values 
)

Set the joint state goal for a particular joint.

Definition at line 1020 of file move_group.cpp.

bool moveit::planning_interface::MoveGroup::setJointValueTarget ( const std::string &  joint_name,
double  value 
)

Set the joint state goal for a particular joint.

Definition at line 1014 of file move_group.cpp.

bool moveit::planning_interface::MoveGroup::setJointValueTarget ( const sensor_msgs::JointState &  state)

Set the joint state goal for a particular joint.

Definition at line 1030 of file move_group.cpp.

bool moveit::planning_interface::MoveGroup::setNamedTarget ( const std::string &  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.

Definition at line 963 of file move_group.cpp.

Set the joint state goal to a random joint configuration.

Definition at line 957 of file move_group.cpp.



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