Representation of a robot's state. This includes position, velocity, acceleration and effort. More...
#include <robot_state.h>
Public Member Functions | |
void | computeAABB (std::vector< double > &aabb) |
Compute an axis-aligned bounding box that contains the current state. The format for aabb is (minx, maxx, miny, maxy, minz, maxz) More... | |
void | computeAABB (std::vector< double > &aabb) const |
Compute an axis-aligned bounding box that contains the current state. The format for aabb is (minx, maxx, miny, maxy, minz, maxz) More... | |
const Eigen::Isometry3d & | getFrameInfo (const std::string &frame_id, const LinkModel *&robot_link, bool &frame_found) const |
Get the transformation matrix from the model frame (root of model) to the frame identified by frame_id. More... | |
const Eigen::Isometry3d & | getFrameTransform (const std::string &frame_id, bool *frame_found=nullptr) |
Get the transformation matrix from the model frame (root of model) to the frame identified by frame_id. More... | |
const Eigen::Isometry3d & | getFrameTransform (const std::string &frame_id, bool *frame_found=nullptr) const |
Get the transformation matrix from the model frame (root of model) to the frame identified by frame_id. More... | |
const JointModel * | getJointModel (const std::string &joint) const |
Get the model of a particular joint. More... | |
const JointModelGroup * | getJointModelGroup (const std::string &group) const |
Get the model of a particular joint group. More... | |
const LinkModel * | getLinkModel (const std::string &link) const |
Get the model of a particular link. More... | |
random_numbers::RandomNumberGenerator & | getRandomNumberGenerator () |
Return the instance of a random number generator. More... | |
void | getRobotMarkers (visualization_msgs::MarkerArray &arr, const std::vector< std::string > &link_names, bool include_attached=false) |
Get a MarkerArray that fully describes the robot markers for a given robot. Update the state first. More... | |
void | getRobotMarkers (visualization_msgs::MarkerArray &arr, const std::vector< std::string > &link_names, bool include_attached=false) const |
Get a MarkerArray that fully describes the robot markers for a given robot. More... | |
void | getRobotMarkers (visualization_msgs::MarkerArray &arr, const std::vector< std::string > &link_names, const std_msgs::ColorRGBA &color, const std::string &ns, const ros::Duration &dur, bool include_attached=false) |
Get a MarkerArray that fully describes the robot markers for a given robot. Update the state first. More... | |
void | getRobotMarkers (visualization_msgs::MarkerArray &arr, const std::vector< std::string > &link_names, const std_msgs::ColorRGBA &color, const std::string &ns, const ros::Duration &dur, bool include_attached=false) const |
Get a MarkerArray that fully describes the robot markers for a given robot. More... | |
const RobotModelConstPtr & | getRobotModel () const |
Get the robot model this state is constructed for. More... | |
std::string | getStateTreeString () const |
std::size_t | getVariableCount () const |
Get the number of variables that make up this state. More... | |
const std::vector< std::string > & | getVariableNames () const |
Get the names of the variables that make up this state, in the order they are stored in memory. More... | |
bool | knowsFrameTransform (const std::string &frame_id) const |
Check if a transformation matrix from the model frame (root of model) to frame frame_id is known. More... | |
RobotState & | operator= (const RobotState &other) |
Copy operator. More... | |
void | printDirtyInfo (std::ostream &out=std::cout) const |
void | printStateInfo (std::ostream &out=std::cout) const |
void | printStatePositions (std::ostream &out=std::cout) const |
void | printStatePositionsWithJointLimits (const moveit::core::JointModelGroup *jmg, std::ostream &out=std::cout) const |
Output to console the current state of the robot's joint limits. More... | |
void | printTransform (const Eigen::Isometry3d &transform, std::ostream &out=std::cout) const |
void | printTransforms (std::ostream &out=std::cout) const |
RobotState (const RobotModelConstPtr &robot_model) | |
A state can be constructed from a specified robot model. No values are initialized. Call setToDefaultValues() if a state needs to provide valid information. More... | |
RobotState (const RobotState &other) | |
Copy constructor. More... | |
bool | setToIKSolverFrame (Eigen::Isometry3d &pose, const kinematics::KinematicsBaseConstPtr &solver) |
Transform pose from the robot model's base frame to the reference frame of the IK solver. More... | |
bool | setToIKSolverFrame (Eigen::Isometry3d &pose, const std::string &ik_frame) |
Transform pose from the robot model's base frame to the reference frame of the IK solver. More... | |
~RobotState () | |
Getting and setting variable position | |
double * | getVariablePositions () |
Get a raw pointer to the positions of the variables stored in this state. Use carefully. If you change these values externally you need to make sure you trigger a forced update for the state by calling update(true). More... | |
const double * | getVariablePositions () const |
Get a raw pointer to the positions of the variables stored in this state. More... | |
void | setVariablePositions (const double *position) |
It is assumed positions is an array containing the new positions for all variables in this state. Those values are copied into the state. More... | |
void | setVariablePositions (const std::vector< double > &position) |
It is assumed positions is an array containing the new positions for all variables in this state. Those values are copied into the state. More... | |
void | setVariablePositions (const std::map< std::string, double > &variable_map) |
Set the positions of a set of variables. If unknown variable names are specified, an exception is thrown. More... | |
void | setVariablePositions (const std::map< std::string, double > &variable_map, std::vector< std::string > &missing_variables) |
Set the positions of a set of variables. If unknown variable names are specified, an exception is thrown. Additionally, missing_variables is filled with the names of the variables that are not set. More... | |
void | setVariablePositions (const std::vector< std::string > &variable_names, const std::vector< double > &variable_position) |
Set the positions of a set of variables. If unknown variable names are specified, an exception is thrown. Additionally, missing_variables is filled with the names of the variables that are not set. More... | |
void | setVariablePosition (const std::string &variable, double value) |
Set the position of a single variable. An exception is thrown if the variable name is not known. More... | |
void | setVariablePosition (int index, double value) |
Set the position of a single variable. The variable is specified by its index (a value associated by the RobotModel to each variable) More... | |
double | getVariablePosition (const std::string &variable) const |
Get the position of a particular variable. An exception is thrown if the variable is not known. More... | |
double | getVariablePosition (int index) const |
Get the position of a particular variable. The variable is specified by its index. No checks are performed for the validity of the index passed More... | |
Getting and setting variable velocity | |
bool | hasVelocities () const |
By default, if velocities are never set or initialized, the state remembers that there are no velocities set. This is useful to know when serializing or copying the state. More... | |
double * | getVariableVelocities () |
Get raw access to the velocities of the variables that make up this state. The values are in the same order as reported by getVariableNames() More... | |
const double * | getVariableVelocities () const |
Get const access to the velocities of the variables that make up this state. The values are in the same order as reported by getVariableNames() More... | |
void | zeroVelocities () |
Set all velocities to 0.0. More... | |
void | setVariableVelocities (const double *velocity) |
Given an array with velocity values for all variables, set those values as the velocities in this state. More... | |
void | setVariableVelocities (const std::vector< double > &velocity) |
Given an array with velocity values for all variables, set those values as the velocities in this state. More... | |
void | setVariableVelocities (const std::map< std::string, double > &variable_map) |
Set the velocities of a set of variables. If unknown variable names are specified, an exception is thrown. More... | |
void | setVariableVelocities (const std::map< std::string, double > &variable_map, std::vector< std::string > &missing_variables) |
Set the velocities of a set of variables. If unknown variable names are specified, an exception is thrown. Additionally, missing_variables is filled with the names of the variables that are not set. More... | |
void | setVariableVelocities (const std::vector< std::string > &variable_names, const std::vector< double > &variable_velocity) |
Set the velocities of a set of variables. If unknown variable names are specified, an exception is thrown. More... | |
void | setVariableVelocity (const std::string &variable, double value) |
Set the velocity of a variable. If an unknown variable name is specified, an exception is thrown. More... | |
void | setVariableVelocity (int index, double value) |
Set the velocity of a single variable. The variable is specified by its index (a value associated by the RobotModel to each variable) More... | |
double | getVariableVelocity (const std::string &variable) const |
Get the velocity of a particular variable. An exception is thrown if the variable is not known. More... | |
double | getVariableVelocity (int index) const |
Get the velocity of a particular variable. The variable is specified by its index. No checks are performed for the validity of the index passed More... | |
void | dropVelocities () |
Remove velocities from this state (this differs from setting them to zero) More... | |
Getting and setting variable acceleration | |
bool | hasAccelerations () const |
By default, if accelerations are never set or initialized, the state remembers that there are no accelerations set. This is useful to know when serializing or copying the state. If hasAccelerations() reports true, hasEffort() will certainly report false. More... | |
double * | getVariableAccelerations () |
Get raw access to the accelerations of the variables that make up this state. The values are in the same order as reported by getVariableNames(). The area of memory overlaps with effort (effort and acceleration should not be set at the same time) More... | |
const double * | getVariableAccelerations () const |
Get const raw access to the accelerations of the variables that make up this state. The values are in the same order as reported by getVariableNames() More... | |
void | zeroAccelerations () |
Set all accelerations to 0.0. More... | |
void | setVariableAccelerations (const double *acceleration) |
Given an array with acceleration values for all variables, set those values as the accelerations in this state. More... | |
void | setVariableAccelerations (const std::vector< double > &acceleration) |
Given an array with acceleration values for all variables, set those values as the accelerations in this state. More... | |
void | setVariableAccelerations (const std::map< std::string, double > &variable_map) |
Set the accelerations of a set of variables. If unknown variable names are specified, an exception is thrown. More... | |
void | setVariableAccelerations (const std::map< std::string, double > &variable_map, std::vector< std::string > &missing_variables) |
Set the accelerations of a set of variables. If unknown variable names are specified, an exception is thrown. Additionally, missing_variables is filled with the names of the variables that are not set. More... | |
void | setVariableAccelerations (const std::vector< std::string > &variable_names, const std::vector< double > &variable_acceleration) |
Set the accelerations of a set of variables. If unknown variable names are specified, an exception is thrown. More... | |
void | setVariableAcceleration (const std::string &variable, double value) |
Set the acceleration of a variable. If an unknown variable name is specified, an exception is thrown. More... | |
void | setVariableAcceleration (int index, double value) |
Set the acceleration of a single variable. The variable is specified by its index (a value associated by the RobotModel to each variable) More... | |
double | getVariableAcceleration (const std::string &variable) const |
Get the acceleration of a particular variable. An exception is thrown if the variable is not known. More... | |
double | getVariableAcceleration (int index) const |
Get the acceleration of a particular variable. The variable is specified by its index. No checks are performed for the validity of the index passed More... | |
void | dropAccelerations () |
Remove accelerations from this state (this differs from setting them to zero) More... | |
Getting and setting variable effort | |
bool | hasEffort () const |
By default, if effort is never set or initialized, the state remembers that there is no effort set. This is useful to know when serializing or copying the state. If hasEffort() reports true, hasAccelerations() will certainly report false. More... | |
double * | getVariableEffort () |
Get raw access to the effort of the variables that make up this state. The values are in the same order as reported by getVariableNames(). The area of memory overlaps with accelerations (effort and acceleration should not be set at the same time) More... | |
const double * | getVariableEffort () const |
Get const raw access to the effort of the variables that make up this state. The values are in the same order as reported by getVariableNames(). More... | |
void | zeroEffort () |
Set all effort values to 0.0. More... | |
void | setVariableEffort (const double *effort) |
Given an array with effort values for all variables, set those values as the effort in this state. More... | |
void | setVariableEffort (const std::vector< double > &effort) |
Given an array with effort values for all variables, set those values as the effort in this state. More... | |
void | setVariableEffort (const std::map< std::string, double > &variable_map) |
Set the effort of a set of variables. If unknown variable names are specified, an exception is thrown. More... | |
void | setVariableEffort (const std::map< std::string, double > &variable_map, std::vector< std::string > &missing_variables) |
Set the effort of a set of variables. If unknown variable names are specified, an exception is thrown. Additionally, missing_variables is filled with the names of the variables that are not set. More... | |
void | setVariableEffort (const std::vector< std::string > &variable_names, const std::vector< double > &variable_acceleration) |
Set the effort of a set of variables. If unknown variable names are specified, an exception is thrown. More... | |
void | setVariableEffort (const std::string &variable, double value) |
Set the effort of a variable. If an unknown variable name is specified, an exception is thrown. More... | |
void | setVariableEffort (int index, double value) |
Set the effort of a single variable. The variable is specified by its index (a value associated by the RobotModel to each variable) More... | |
double | getVariableEffort (const std::string &variable) const |
Get the effort of a particular variable. An exception is thrown if the variable is not known. More... | |
double | getVariableEffort (int index) const |
Get the effort of a particular variable. The variable is specified by its index. No checks are performed for the validity of the index passed More... | |
void | dropEffort () |
Remove effort values from this state (this differs from setting them to zero) More... | |
void | dropDynamics () |
Reduce RobotState to kinematic information (remove velocity, acceleration and effort, if present) More... | |
void | invertVelocity () |
Invert velocity if present. More... | |
Getting and setting joint positions, velocities, accelerations and effort for a single joint | |
The joint might be multi-DOF, i.e. require more than one variable to set. See setVariablePositions(), setVariableVelocities(), setVariableEffort() to handle multiple joints. | |
void | setJointPositions (const std::string &joint_name, const double *position) |
void | setJointPositions (const std::string &joint_name, const std::vector< double > &position) |
void | setJointPositions (const JointModel *joint, const std::vector< double > &position) |
void | setJointPositions (const JointModel *joint, const double *position) |
void | setJointPositions (const std::string &joint_name, const Eigen::Isometry3d &transform) |
void | setJointPositions (const JointModel *joint, const Eigen::Isometry3d &transform) |
void | setJointVelocities (const JointModel *joint, const double *velocity) |
void | setJointEfforts (const JointModel *joint, const double *effort) |
const double * | getJointPositions (const std::string &joint_name) const |
const double * | getJointPositions (const JointModel *joint) const |
const double * | getJointVelocities (const std::string &joint_name) const |
const double * | getJointVelocities (const JointModel *joint) const |
const double * | getJointAccelerations (const std::string &joint_name) const |
const double * | getJointAccelerations (const JointModel *joint) const |
const double * | getJointEffort (const std::string &joint_name) const |
const double * | getJointEffort (const JointModel *joint) const |
Getting and setting group positions | |
void | setJointGroupPositions (const std::string &joint_group_name, const double *gstate) |
Given positions for the variables that make up a group, in the order found in the group (including values of mimic joints), set those as the new values that correspond to the group. More... | |
void | setJointGroupPositions (const std::string &joint_group_name, const std::vector< double > &gstate) |
Given positions for the variables that make up a group, in the order found in the group (including values of mimic joints), set those as the new values that correspond to the group. More... | |
void | setJointGroupPositions (const JointModelGroup *group, const std::vector< double > &gstate) |
Given positions for the variables that make up a group, in the order found in the group (including values of mimic joints), set those as the new values that correspond to the group. More... | |
void | setJointGroupPositions (const JointModelGroup *group, const double *gstate) |
Given positions for the variables that make up a group, in the order found in the group (including values of mimic joints), set those as the new values that correspond to the group. More... | |
void | setJointGroupPositions (const std::string &joint_group_name, const Eigen::VectorXd &values) |
Given positions for the variables that make up a group, in the order found in the group (including values of mimic joints), set those as the new values that correspond to the group. More... | |
void | setJointGroupPositions (const JointModelGroup *group, const Eigen::VectorXd &values) |
Given positions for the variables that make up a group, in the order found in the group (including values of mimic joints), set those as the new values that correspond to the group. More... | |
void | setJointGroupActivePositions (const JointModelGroup *group, const std::vector< double > &gstate) |
Given positions for the variables of active joints that make up a group, in the order found in the group (excluding values of mimic joints), set those as the new values that correspond to the group. More... | |
void | setJointGroupActivePositions (const std::string &joint_group_name, const std::vector< double > &gstate) |
Given positions for the variables of active joints that make up a group, in the order found in the group (excluding values of mimic joints), set those as the new values that correspond to the group. More... | |
void | setJointGroupActivePositions (const JointModelGroup *group, const Eigen::VectorXd &values) |
Given positions for the variables of active joints that make up a group, in the order found in the group (excluding values of mimic joints), set those as the new values that correspond to the group. More... | |
void | setJointGroupActivePositions (const std::string &joint_group_name, const Eigen::VectorXd &values) |
Given positions for the variables of active joints that make up a group, in the order found in the group (excluding values of mimic joints), set those as the new values that correspond to the group. More... | |
void | copyJointGroupPositions (const std::string &joint_group_name, std::vector< double > &gstate) const |
For a given group, copy the position values of the variables that make up the group into another location, in the order that the variables are found in the group. This is not necessarily a contiguous block of memory in the RobotState itself, so we copy instead of returning a pointer. More... | |
void | copyJointGroupPositions (const std::string &joint_group_name, double *gstate) const |
For a given group, copy the position values of the variables that make up the group into another location, in the order that the variables are found in the group. This is not necessarily a contiguous block of memory in the RobotState itself, so we copy instead of returning a pointer. More... | |
void | copyJointGroupPositions (const JointModelGroup *group, std::vector< double > &gstate) const |
For a given group, copy the position values of the variables that make up the group into another location, in the order that the variables are found in the group. This is not necessarily a contiguous block of memory in the RobotState itself, so we copy instead of returning a pointer. More... | |
void | copyJointGroupPositions (const JointModelGroup *group, double *gstate) const |
For a given group, copy the position values of the variables that make up the group into another location, in the order that the variables are found in the group. This is not necessarily a contiguous block of memory in the RobotState itself, so we copy instead of returning a pointer. More... | |
void | copyJointGroupPositions (const std::string &joint_group_name, Eigen::VectorXd &values) const |
For a given group, copy the position values of the variables that make up the group into another location, in the order that the variables are found in the group. This is not necessarily a contiguous block of memory in the RobotState itself, so we copy instead of returning a pointer. More... | |
void | copyJointGroupPositions (const JointModelGroup *group, Eigen::VectorXd &values) const |
For a given group, copy the position values of the variables that make up the group into another location, in the order that the variables are found in the group. This is not necessarily a contiguous block of memory in the RobotState itself, so we copy instead of returning a pointer. More... | |
Getting and setting group velocities | |
void | setJointGroupVelocities (const std::string &joint_group_name, const double *gstate) |
Given velocities for the variables that make up a group, in the order found in the group (including values of mimic joints), set those as the new values that correspond to the group. More... | |
void | setJointGroupVelocities (const std::string &joint_group_name, const std::vector< double > &gstate) |
Given velocities for the variables that make up a group, in the order found in the group (including values of mimic joints), set those as the new values that correspond to the group. More... | |
void | setJointGroupVelocities (const JointModelGroup *group, const std::vector< double > &gstate) |
Given velocities for the variables that make up a group, in the order found in the group (including values of mimic joints), set those as the new values that correspond to the group. More... | |
void | setJointGroupVelocities (const JointModelGroup *group, const double *gstate) |
Given velocities for the variables that make up a group, in the order found in the group (including values of mimic joints), set those as the new values that correspond to the group. More... | |
void | setJointGroupVelocities (const std::string &joint_group_name, const Eigen::VectorXd &values) |
Given velocities for the variables that make up a group, in the order found in the group (including values of mimic joints), set those as the new values that correspond to the group. More... | |
void | setJointGroupVelocities (const JointModelGroup *group, const Eigen::VectorXd &values) |
Given velocities for the variables that make up a group, in the order found in the group (including values of mimic joints), set those as the new values that correspond to the group. More... | |
void | copyJointGroupVelocities (const std::string &joint_group_name, std::vector< double > &gstate) const |
For a given group, copy the velocity values of the variables that make up the group into another location, in the order that the variables are found in the group. This is not necessarily a contiguous block of memory in the RobotState itself, so we copy instead of returning a pointer. More... | |
void | copyJointGroupVelocities (const std::string &joint_group_name, double *gstate) const |
For a given group, copy the velocity values of the variables that make up the group into another location, in the order that the variables are found in the group. This is not necessarily a contiguous block of memory in the RobotState itself, so we copy instead of returning a pointer. More... | |
void | copyJointGroupVelocities (const JointModelGroup *group, std::vector< double > &gstate) const |
For a given group, copy the velocity values of the variables that make up the group into another location, in the order that the variables are found in the group. This is not necessarily a contiguous block of memory in the RobotState itself, so we copy instead of returning a pointer. More... | |
void | copyJointGroupVelocities (const JointModelGroup *group, double *gstate) const |
For a given group, copy the velocity values of the variables that make up the group into another location, in the order that the variables are found in the group. This is not necessarily a contiguous block of memory in the RobotState itself, so we copy instead of returning a pointer. More... | |
void | copyJointGroupVelocities (const std::string &joint_group_name, Eigen::VectorXd &values) const |
For a given group, copy the velocity values of the variables that make up the group into another location, in the order that the variables are found in the group. This is not necessarily a contiguous block of memory in the RobotState itself, so we copy instead of returning a pointer. More... | |
void | copyJointGroupVelocities (const JointModelGroup *group, Eigen::VectorXd &values) const |
For a given group, copy the velocity values of the variables that make up the group into another location, in the order that the variables are found in the group. This is not necessarily a contiguous block of memory in the RobotState itself, so we copy instead of returning a pointer. More... | |
Getting and setting group accelerations | |
void | setJointGroupAccelerations (const std::string &joint_group_name, const double *gstate) |
Given accelerations for the variables that make up a group, in the order found in the group (including values of mimic joints), set those as the new values that correspond to the group. More... | |
void | setJointGroupAccelerations (const std::string &joint_group_name, const std::vector< double > &gstate) |
Given accelerations for the variables that make up a group, in the order found in the group (including values of mimic joints), set those as the new values that correspond to the group. More... | |
void | setJointGroupAccelerations (const JointModelGroup *group, const std::vector< double > &gstate) |
Given accelerations for the variables that make up a group, in the order found in the group (including values of mimic joints), set those as the new values that correspond to the group. More... | |
void | setJointGroupAccelerations (const JointModelGroup *group, const double *gstate) |
Given accelerations for the variables that make up a group, in the order found in the group (including values of mimic joints), set those as the new values that correspond to the group. More... | |
void | setJointGroupAccelerations (const std::string &joint_group_name, const Eigen::VectorXd &values) |
Given accelerations for the variables that make up a group, in the order found in the group (including values of mimic joints), set those as the new values that correspond to the group. More... | |
void | setJointGroupAccelerations (const JointModelGroup *group, const Eigen::VectorXd &values) |
Given accelerations for the variables that make up a group, in the order found in the group (including values of mimic joints), set those as the new values that correspond to the group. More... | |
void | copyJointGroupAccelerations (const std::string &joint_group_name, std::vector< double > &gstate) const |
For a given group, copy the acceleration values of the variables that make up the group into another location, in the order that the variables are found in the group. This is not necessarily a contiguous block of memory in the RobotState itself, so we copy instead of returning a pointer. More... | |
void | copyJointGroupAccelerations (const std::string &joint_group_name, double *gstate) const |
For a given group, copy the acceleration values of the variables that make up the group into another location, in the order that the variables are found in the group. This is not necessarily a contiguous block of memory in the RobotState itself, so we copy instead of returning a pointer. More... | |
void | copyJointGroupAccelerations (const JointModelGroup *group, std::vector< double > &gstate) const |
For a given group, copy the acceleration values of the variables that make up the group into another location, in the order that the variables are found in the group. This is not necessarily a contiguous block of memory in the RobotState itself, so we copy instead of returning a pointer. More... | |
void | copyJointGroupAccelerations (const JointModelGroup *group, double *gstate) const |
For a given group, copy the acceleration values of the variables that make up the group into another location, in the order that the variables are found in the group. This is not necessarily a contiguous block of memory in the RobotState itself, so we copy instead of returning a pointer. More... | |
void | copyJointGroupAccelerations (const std::string &joint_group_name, Eigen::VectorXd &values) const |
For a given group, copy the acceleration values of the variables that make up the group into another location, in the order that the variables are found in the group. This is not necessarily a contiguous block of memory in the RobotState itself, so we copy instead of returning a pointer. More... | |
void | copyJointGroupAccelerations (const JointModelGroup *group, Eigen::VectorXd &values) const |
For a given group, copy the acceleration values of the variables that make up the group into another location, in the order that the variables are found in the group. This is not necessarily a contiguous block of memory in the RobotState itself, so we copy instead of returning a pointer. More... | |
Setting from Inverse Kinematics | |
bool | setFromIK (const JointModelGroup *group, const geometry_msgs::Pose &pose, double timeout=0.0, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) |
If the group this state corresponds to is a chain and a solver is available, then the joint values can be set by computing inverse kinematics. The pose is assumed to be in the reference frame of the kinematic model. Returns true on success. More... | |
bool | setFromIK (const JointModelGroup *group, const geometry_msgs::Pose &pose, unsigned int, double timeout=0.0, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) |
bool | setFromIK (const JointModelGroup *group, const geometry_msgs::Pose &pose, const std::string &tip, double timeout=0.0, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) |
If the group this state corresponds to is a chain and a solver is available, then the joint values can be set by computing inverse kinematics. The pose is assumed to be in the reference frame of the kinematic model. Returns true on success. More... | |
bool | setFromIK (const JointModelGroup *group, const geometry_msgs::Pose &pose, const std::string &tip, unsigned int, double timeout=0.0, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) |
bool | setFromIK (const JointModelGroup *group, const Eigen::Isometry3d &pose, double timeout=0.0, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) |
If the group this state corresponds to is a chain and a solver is available, then the joint values can be set by computing inverse kinematics. The pose is assumed to be in the reference frame of the kinematic model. Returns true on success. More... | |
bool | setFromIK (const JointModelGroup *group, const Eigen::Isometry3d &pose, unsigned int, double timeout=0.0, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) |
bool | setFromIK (const JointModelGroup *group, const Eigen::Isometry3d &pose, const std::string &tip, double timeout=0.0, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) |
If the group this state corresponds to is a chain and a solver is available, then the joint values can be set by computing inverse kinematics. The pose is assumed to be in the reference frame of the kinematic model. Returns true on success. More... | |
bool | setFromIK (const JointModelGroup *group, const Eigen::Isometry3d &pose, const std::string &tip, unsigned int, double timeout=0.0, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) |
bool | setFromIK (const JointModelGroup *group, const Eigen::Isometry3d &pose, const std::string &tip, const std::vector< double > &consistency_limits, double timeout=0.0, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) |
If the group this state corresponds to is a chain and a solver is available, then the joint values can be set by computing inverse kinematics. The pose is assumed to be in the reference frame of the kinematic model. Returns true on success. More... | |
bool | setFromIK (const JointModelGroup *group, const Eigen::Isometry3d &pose, const std::string &tip, const std::vector< double > &consistency_limits, unsigned int, double timeout=0.0, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) |
bool | setFromIK (const JointModelGroup *group, const EigenSTL::vector_Isometry3d &poses, const std::vector< std::string > &tips, double timeout=0.0, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) |
Warning: This function inefficiently copies all transforms around. If the group consists of a set of sub-groups that are each a chain and a solver is available for each sub-group, then the joint values can be set by computing inverse kinematics. The poses are assumed to be in the reference frame of the kinematic model. The poses are assumed to be in the same order as the order of the sub-groups in this group. Returns true on success. More... | |
bool | setFromIK (const JointModelGroup *group, const EigenSTL::vector_Isometry3d &poses, const std::vector< std::string > &tips, unsigned int, double timeout=0.0, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) |
bool | setFromIK (const JointModelGroup *group, const EigenSTL::vector_Isometry3d &poses, const std::vector< std::string > &tips, const std::vector< std::vector< double >> &consistency_limits, double timeout=0.0, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) |
Warning: This function inefficiently copies all transforms around. If the group consists of a set of sub-groups that are each a chain and a solver is available for each sub-group, then the joint values can be set by computing inverse kinematics. The poses are assumed to be in the reference frame of the kinematic model. The poses are assumed to be in the same order as the order of the sub-groups in this group. Returns true on success. More... | |
bool | setFromIK (const JointModelGroup *group, const EigenSTL::vector_Isometry3d &poses, const std::vector< std::string > &tips, const std::vector< std::vector< double >> &consistency_limits, unsigned int, double timeout=0.0, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) |
bool | setFromIKSubgroups (const JointModelGroup *group, const EigenSTL::vector_Isometry3d &poses, const std::vector< std::string > &tips, const std::vector< std::vector< double >> &consistency_limits, double timeout=0.0, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) |
setFromIK for multiple poses and tips (end effectors) when no solver exists for the jmg that can solver for non-chain kinematics. In this case, we divide the group into subgroups and do IK solving individually More... | |
bool | setFromIKSubgroups (const JointModelGroup *group, const EigenSTL::vector_Isometry3d &poses, const std::vector< std::string > &tips, const std::vector< std::vector< double >> &consistency_limits, unsigned int, double timeout=0.0, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) |
bool | setFromDiffIK (const JointModelGroup *group, const Eigen::VectorXd &twist, const std::string &tip, double dt, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn()) |
Set the joint values from a Cartesian velocity applied during a time dt. More... | |
bool | setFromDiffIK (const JointModelGroup *group, const geometry_msgs::Twist &twist, const std::string &tip, double dt, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn()) |
Set the joint values from a Cartesian velocity applied during a time dt. More... | |
bool | getJacobian (const JointModelGroup *group, const LinkModel *link, const Eigen::Vector3d &reference_point_position, Eigen::MatrixXd &jacobian, bool use_quaternion_representation=false) const |
Compute the Jacobian with reference to a particular point on a given link, for a specified group. More... | |
bool | getJacobian (const JointModelGroup *group, const LinkModel *link, const Eigen::Vector3d &reference_point_position, Eigen::MatrixXd &jacobian, bool use_quaternion_representation=false) |
Compute the Jacobian with reference to a particular point on a given link, for a specified group. More... | |
Eigen::MatrixXd | getJacobian (const JointModelGroup *group, const Eigen::Vector3d &reference_point_position=Eigen::Vector3d(0.0, 0.0, 0.0)) const |
Compute the Jacobian with reference to the last link of a specified group. If the group is not a chain, an exception is thrown. More... | |
Eigen::MatrixXd | getJacobian (const JointModelGroup *group, const Eigen::Vector3d &reference_point_position=Eigen::Vector3d(0.0, 0.0, 0.0)) |
Compute the Jacobian with reference to the last link of a specified group. If the group is not a chain, an exception is thrown. More... | |
void | computeVariableVelocity (const JointModelGroup *jmg, Eigen::VectorXd &qdot, const Eigen::VectorXd &twist, const LinkModel *tip) const |
Given a twist for a particular link (tip), compute the corresponding velocity for every variable and store it in qdot. More... | |
void | computeVariableVelocity (const JointModelGroup *jmg, Eigen::VectorXd &qdot, const Eigen::VectorXd &twist, const LinkModel *tip) |
Given a twist for a particular link (tip), compute the corresponding velocity for every variable and store it in qdot. More... | |
bool | integrateVariableVelocity (const JointModelGroup *jmg, const Eigen::VectorXd &qdot, double dt, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn()) |
Given the velocities for the variables in this group (qdot) and an amount of time (dt), update the current state using the Euler forward method. If the constraint specified is satisfied, return true, otherwise return false. More... | |
Getting and setting whole states | |
void | setVariableValues (const sensor_msgs::JointState &msg) |
void | setToDefaultValues () |
Set all joints to their default positions. The default position is 0, or if that is not within bounds then half way between min and max bound. More... | |
bool | setToDefaultValues (const JointModelGroup *group, const std::string &name) |
Set the joints in group to the position name defined in the SRDF. More... | |
bool | setToDefaultValues (const std::string &group_name, const std::string &state_name) |
void | setToRandomPositions () |
Set all joints to random values. Values will be within default bounds. More... | |
void | setToRandomPositions (random_numbers::RandomNumberGenerator &rng) |
Set all joints to random values using the specified random number generator. Values will be within default bounds. More... | |
void | setToRandomPositions (const JointModelGroup *group) |
Set all joints in group to random values. Values will be within default bounds. More... | |
void | setToRandomPositions (const JointModelGroup *group, random_numbers::RandomNumberGenerator &rng) |
Set all joints in group to random values using a specified random number generator. Values will be within default bounds. More... | |
void | setToRandomPositionsNearBy (const JointModelGroup *group, const RobotState &seed, double distance) |
Set all joints in group to random values near the value in seed. distance is the maximum amount each joint value will vary from the corresponding value in seed. distance represents meters for prismatic/postitional joints and radians for revolute/orientation joints. Resulting values are clamped within default bounds. More... | |
void | setToRandomPositionsNearBy (const JointModelGroup *group, const RobotState &seed, double distance, random_numbers::RandomNumberGenerator &rng) |
Set all joints in group to random values near the value in seed, using a specified random number generator. distance is the maximum amount each joint value will vary from the corresponding value in seed. distance represents meters for prismatic/postitional joints and radians for revolute/orientation joints. Resulting values are clamped within default bounds. More... | |
void | setToRandomPositionsNearBy (const JointModelGroup *group, const RobotState &seed, const std::vector< double > &distances) |
Set all joints in group to random values near the value in seed. distances MUST have the same size as group.getActiveJointModels() . Each value in distances is the maximum amount the corresponding active joint in group will vary from the corresponding value in seed. distance represents meters for prismatic/postitional joints and radians for revolute/orientation joints. Resulting values are clamped within default bounds. More... | |
void | setToRandomPositionsNearBy (const JointModelGroup *group, const RobotState &seed, const std::vector< double > &distances, random_numbers::RandomNumberGenerator &rng) |
Set all joints in group to random values near the value in seed, using a specified random number generator. distances MUST have the same size as group.getActiveJointModels() . Each value in distances is the maximum amount the corresponding active joint in group will vary from the corresponding value in seed. distance represents meters for prismatic/postitional joints and radians for revolute/orientation joints. Resulting values are clamped within default bounds. More... | |
Updating and getting transforms | |
void | updateCollisionBodyTransforms () |
Update the transforms for the collision bodies. This call is needed before calling collision checking. If updating link transforms or joint transorms is needed, the corresponding updates are also triggered. More... | |
void | updateLinkTransforms () |
Update the reference frame transforms for links. This call is needed before using the transforms of links for coordinate transforms. More... | |
void | update (bool force=false) |
Update all transforms. More... | |
void | updateStateWithLinkAt (const std::string &link_name, const Eigen::Isometry3d &transform, bool backward=false) |
Update the state after setting a particular link to the input global transform pose. More... | |
void | updateStateWithLinkAt (const LinkModel *link, const Eigen::Isometry3d &transform, bool backward=false) |
Update the state after setting a particular link to the input global transform pose. More... | |
const moveit::core::LinkModel * | getRigidlyConnectedParentLinkModel (const std::string &frame, Eigen::Isometry3d *transform=nullptr, const moveit::core::JointModelGroup *jmg=nullptr) const |
Get the latest link upwards the kinematic tree which is only connected via fixed joints. More... | |
const Eigen::Isometry3d & | getGlobalLinkTransform (const std::string &link_name) |
Get the link transform w.r.t. the root link (model frame) of the RobotModel. This is typically the root link of the URDF unless a virtual joint is present. Checks the cache and if there are any dirty (non-updated) transforms, first updates them as needed. A related, more comprehensive function is |getFrameTransform|, which additionally to link frames also searches for attached object frames and their subframes. More... | |
const Eigen::Isometry3d & | getGlobalLinkTransform (const LinkModel *link) |
const Eigen::Isometry3d & | getGlobalLinkTransform (const std::string &link_name) const |
const Eigen::Isometry3d & | getGlobalLinkTransform (const LinkModel *link) const |
const Eigen::Isometry3d & | getCollisionBodyTransform (const std::string &link_name, std::size_t index) |
Get the link transform w.r.t. the root link (model frame) of the RobotModel. This is typically the root link of the URDF unless a virtual joint is present. Checks the cache and if there are any dirty (non-updated) transforms, first updates them as needed. More... | |
const Eigen::Isometry3d & | getCollisionBodyTransform (const LinkModel *link, std::size_t index) |
const Eigen::Isometry3d & | getCollisionBodyTransform (const std::string &link_name, std::size_t index) const |
const Eigen::Isometry3d & | getCollisionBodyTransform (const LinkModel *link, std::size_t index) const |
const Eigen::Isometry3d & | getJointTransform (const std::string &joint_name) |
const Eigen::Isometry3d & | getJointTransform (const JointModel *joint) |
const Eigen::Isometry3d & | getJointTransform (const std::string &joint_name) const |
const Eigen::Isometry3d & | getJointTransform (const JointModel *joint) const |
bool | dirtyJointTransform (const JointModel *joint) const |
bool | dirtyLinkTransforms () const |
bool | dirtyCollisionBodyTransforms () const |
bool | dirty () const |
Returns true if anything in this state is dirty. More... | |
Computing distances | |
double | distance (const RobotState &other) const |
Return the sum of joint distances to "other" state. Only considers active joints. More... | |
double | distance (const RobotState &other, const JointModelGroup *joint_group) const |
Return the sum of joint distances to "other" state. Only considers active joints. More... | |
double | distance (const RobotState &other, const JointModel *joint) const |
Return the sum of joint distances to "other" state. Only considers active joints. More... | |
void | interpolate (const RobotState &to, double t, RobotState &state) const |
void | interpolate (const RobotState &to, double t, RobotState &state, const JointModelGroup *joint_group) const |
void | interpolate (const RobotState &to, double t, RobotState &state, const JointModel *joint) const |
void | enforceBounds () |
void | enforceBounds (const JointModelGroup *joint_group) |
void | enforceBounds (const JointModel *joint) |
void | enforcePositionBounds (const JointModel *joint) |
void | harmonizePositions () |
Call harmonizePosition() for all joints / all joints in group / given joint. More... | |
void | harmonizePositions (const JointModelGroup *joint_group) |
void | harmonizePosition (const JointModel *joint) |
void | enforceVelocityBounds (const JointModel *joint) |
bool | satisfiesBounds (double margin=0.0) const |
bool | satisfiesBounds (const JointModelGroup *joint_group, double margin=0.0) const |
bool | satisfiesBounds (const JointModel *joint, double margin=0.0) const |
bool | satisfiesPositionBounds (const JointModel *joint, double margin=0.0) const |
bool | satisfiesVelocityBounds (const JointModel *joint, double margin=0.0) const |
std::pair< double, const JointModel * > | getMinDistanceToPositionBounds () const |
Get the minimm distance from this state to the bounds. The minimum distance and the joint for which this minimum is achieved are returned. More... | |
std::pair< double, const JointModel * > | getMinDistanceToPositionBounds (const JointModelGroup *group) const |
Get the minimm distance from a group in this state to the bounds. The minimum distance and the joint for which this minimum is achieved are returned. More... | |
std::pair< double, const JointModel * > | getMinDistanceToPositionBounds (const std::vector< const JointModel * > &joints) const |
Get the minimm distance from a set of joints in the state to the bounds. The minimum distance and the joint for which this minimum is achieved are returned. More... | |
bool | isValidVelocityMove (const RobotState &other, const JointModelGroup *group, double dt) const |
Check that the time to move between two waypoints is sufficient given velocity limits and time step. More... | |
Managing attached bodies | |
void | attachBody (std::unique_ptr< AttachedBody > attached_body) |
Add an attached body to this state. More... | |
void | attachBody (AttachedBody *attached_body) |
Add an attached body to this state. Ownership of the memory for the attached body is assumed by the state. More... | |
void | attachBody (const std::string &id, const Eigen::Isometry3d &pose, const std::vector< shapes::ShapeConstPtr > &shapes, const EigenSTL::vector_Isometry3d &shape_poses, const std::set< std::string > &touch_links, const std::string &link_name, const trajectory_msgs::JointTrajectory &detach_posture=trajectory_msgs::JointTrajectory(), const moveit::core::FixedTransformsMap &subframe_poses=moveit::core::FixedTransformsMap()) |
Add an attached body to a link. More... | |
void | attachBody (const std::string &id, const Eigen::Isometry3d &pose, const std::vector< shapes::ShapeConstPtr > &shapes, const EigenSTL::vector_Isometry3d &shape_poses, const std::vector< std::string > &touch_links, const std::string &link_name, const trajectory_msgs::JointTrajectory &detach_posture=trajectory_msgs::JointTrajectory(), const moveit::core::FixedTransformsMap &subframe_poses=moveit::core::FixedTransformsMap()) |
Add an attached body to a link. More... | |
void | getAttachedBodies (std::vector< const AttachedBody * > &attached_bodies) const |
Get all bodies attached to the model corresponding to this state. More... | |
void | getAttachedBodies (std::vector< const AttachedBody * > &attached_bodies, const JointModelGroup *group) const |
Get all bodies attached to a particular group the model corresponding to this state. More... | |
void | getAttachedBodies (std::vector< const AttachedBody * > &attached_bodies, const LinkModel *link_model) const |
Get all bodies attached to a particular link in the model corresponding to this state. More... | |
bool | clearAttachedBody (const std::string &id) |
Remove the attached body named id. Return false if the object was not found (and thus not removed). Return true on success. More... | |
void | clearAttachedBodies (const LinkModel *link) |
Clear the bodies attached to a specific link. More... | |
void | clearAttachedBodies (const JointModelGroup *group) |
Clear the bodies attached to a specific group. More... | |
void | clearAttachedBodies () |
Clear all attached bodies. This calls delete on the AttachedBody instances, if needed. More... | |
const AttachedBody * | getAttachedBody (const std::string &name) const |
Get the attached body named name. Return NULL if not found. More... | |
bool | hasAttachedBody (const std::string &id) const |
Check if an attached body named id exists in this state. More... | |
void | setAttachedBodyUpdateCallback (const AttachedBodyCallback &callback) |
Private Member Functions | |
void | allocMemory () |
bool | checkCollisionTransforms () const |
This function is only called in debug mode. More... | |
bool | checkJointTransforms (const JointModel *joint) const |
This function is only called in debug mode. More... | |
bool | checkLinkTransforms () const |
This function is only called in debug mode. More... | |
void | copyFrom (const RobotState &other) |
void | getMissingKeys (const std::map< std::string, double > &variable_map, std::vector< std::string > &missing_variables) const |
void | getStateTreeJointString (std::ostream &ss, const JointModel *jm, const std::string &pfx0, bool last) const |
void | initTransforms () |
void | markAcceleration () |
void | markDirtyJointTransforms (const JointModel *joint) |
void | markDirtyJointTransforms (const JointModelGroup *group) |
void | markEffort () |
void | markVelocity () |
void | updateLinkTransformsInternal (const JointModel *start) |
void | updateMimicJoint (const JointModel *joint) |
void | updateMimicJoint (const std::vector< const JointModel * > &mim) |
Update a set of joints that are certain to be mimicking other joints. More... | |
void | updateMimicJoints (const JointModelGroup *group) |
Update all mimic joints within group. More... | |
Private Attributes | |
double * | acceleration_ |
std::map< std::string, std::unique_ptr< AttachedBody > > | attached_body_map_ |
All attached bodies that are part of this state, indexed by their name. More... | |
AttachedBodyCallback | attached_body_update_callback_ |
This event is called when there is a change in the attached bodies for this state; The event specifies the body that changed and whether it was just attached or about to be detached. More... | |
const JointModel * | dirty_collision_body_transforms_ |
unsigned char * | dirty_joint_transforms_ |
const JointModel * | dirty_link_transforms_ |
double * | effort_ |
Eigen::Isometry3d * | global_collision_body_transforms_ |
Transforms from model frame to collision bodies. More... | |
Eigen::Isometry3d * | global_link_transforms_ |
Transforms from model frame to link frame for each link. More... | |
bool | has_acceleration_ |
bool | has_effort_ |
bool | has_velocity_ |
void * | memory_ |
double * | position_ |
random_numbers::RandomNumberGenerator * | rng_ |
For certain operations a state needs a random number generator. However, it may be slightly expensive to allocate the random number generator if many state instances are generated. For this reason, the generator is allocated on a need basis, by the getRandomNumberGenerator() function. Never use the rng_ member directly, but call getRandomNumberGenerator() instead. More... | |
RobotModelConstPtr | robot_model_ |
Eigen::Isometry3d * | variable_joint_transforms_ |
Local transforms of all joints. More... | |
double * | velocity_ |
Representation of a robot's state. This includes position, velocity, acceleration and effort.
At the lowest level, a state is a collection of variables. Each variable has a name and can have position, velocity, acceleration and effort associated to it. Effort and acceleration share the memory area for efficiency reasons (one should not set both acceleration and effort in the same state and expect things to work). Often variables correspond to joint names as well (joints with one degree of freedom have one variable), but joints with multiple degrees of freedom have more variables. Operations are allowed at variable level, joint level (see JointModel) and joint group level (see JointModelGroup).
For efficiency reasons a state computes forward kinematics in a lazy fashion. This can sometimes lead to problems if the update() function was not called on the state.
Definition at line 155 of file robot_state.h.
moveit::core::RobotState::RobotState | ( | const RobotModelConstPtr & | robot_model | ) |
A state can be constructed from a specified robot model. No values are initialized. Call setToDefaultValues() if a state needs to provide valid information.
Definition at line 125 of file robot_state.cpp.
moveit::core::RobotState::~RobotState | ( | ) |
Definition at line 151 of file robot_state.cpp.
moveit::core::RobotState::RobotState | ( | const RobotState & | other | ) |
Copy constructor.
Definition at line 144 of file robot_state.cpp.
|
private |
Definition at line 159 of file robot_state.cpp.
void moveit::core::RobotState::attachBody | ( | AttachedBody * | attached_body | ) |
Add an attached body to this state. Ownership of the memory for the attached body is assumed by the state.
This only adds the given body to this RobotState instance. It does not change anything about other representations of the object elsewhere in the system. So if the body represents an object in a collision_detection::World (like from a planning_scene::PlanningScene), you will likely need to remove the corresponding object from that world to avoid having collisions detected against it.
Definition at line 1098 of file robot_state.cpp.
void moveit::core::RobotState::attachBody | ( | const std::string & | id, |
const Eigen::Isometry3d & | pose, | ||
const std::vector< shapes::ShapeConstPtr > & | shapes, | ||
const EigenSTL::vector_Isometry3d & | shape_poses, | ||
const std::set< std::string > & | touch_links, | ||
const std::string & | link_name, | ||
const trajectory_msgs::JointTrajectory & | detach_posture = trajectory_msgs::JointTrajectory() , |
||
const moveit::core::FixedTransformsMap & | subframe_poses = moveit::core::FixedTransformsMap() |
||
) |
Add an attached body to a link.
id | The string id associated with the attached body |
pose | The pose associated with the attached body |
shapes | The shapes that make up the attached body |
shape_poses | The transforms between the object pose and the attached body's shapes |
touch_links | The set of links that the attached body is allowed to touch |
link_name | The link to attach to |
detach_posture | The posture of the gripper when placing the object |
subframe_poses | Transforms to points of interest on the object (can be used as end effector link) |
This only adds the given body to this RobotState instance. It does not change anything about other representations of the object elsewhere in the system. So if the body represents an object in a collision_detection::World (like from a planning_scene::PlanningScene), you will likely need to remove the corresponding object from that world to avoid having collisions detected against it.
Definition at line 1103 of file robot_state.cpp.
|
inline |
Add an attached body to a link.
id | The string id associated with the attached body |
pose | The pose associated with the attached body |
shapes | The shapes that make up the attached body |
shape_poses | The transforms between the object pose and the attached body's shapes |
touch_links | The set of links that the attached body is allowed to touch |
link_name | The link to attach to |
detach_posture | The posture of the gripper when placing the object |
subframe_poses | Transforms to points of interest on the object (can be used as end effector link) |
This only adds the given body to this RobotState instance. It does not change anything about other representations of the object elsewhere in the system. So if the body represents an object in a collision_detection::World (like from a planning_scene::PlanningScene), you will likely need to remove the corresponding object from that world to avoid having collisions detected against it.
Definition at line 1704 of file robot_state.h.
void moveit::core::RobotState::attachBody | ( | std::unique_ptr< AttachedBody > | attached_body | ) |
Add an attached body to this state.
This only adds the given body to this RobotState instance. It does not change anything about other representations of the object elsewhere in the system. So if the body represents an object in a collision_detection::World (like from a planning_scene::PlanningScene), you will likely need to remove the corresponding object from that world to avoid having collisions detected against it.
Definition at line 1087 of file robot_state.cpp.
|
private |
This function is only called in debug mode.
Definition at line 274 of file robot_state.cpp.
|
private |
This function is only called in debug mode.
Definition at line 254 of file robot_state.cpp.
|
private |
This function is only called in debug mode.
Definition at line 264 of file robot_state.cpp.
void moveit::core::RobotState::clearAttachedBodies | ( | ) |
Clear all attached bodies. This calls delete on the AttachedBody instances, if needed.
Definition at line 1137 of file robot_state.cpp.
void moveit::core::RobotState::clearAttachedBodies | ( | const JointModelGroup * | group | ) |
Clear the bodies attached to a specific group.
Definition at line 1162 of file robot_state.cpp.
void moveit::core::RobotState::clearAttachedBodies | ( | const LinkModel * | link | ) |
Clear the bodies attached to a specific link.
Definition at line 1147 of file robot_state.cpp.
bool moveit::core::RobotState::clearAttachedBody | ( | const std::string & | id | ) |
Remove the attached body named id. Return false if the object was not found (and thus not removed). Return true on success.
Definition at line 1177 of file robot_state.cpp.
|
inline |
Compute an axis-aligned bounding box that contains the current state. The format for aabb is (minx, maxx, miny, maxy, minz, maxz)
Definition at line 1751 of file robot_state.h.
void moveit::core::RobotState::computeAABB | ( | std::vector< double > & | aabb | ) | const |
Compute an axis-aligned bounding box that contains the current state. The format for aabb is (minx, maxx, miny, maxy, minz, maxz)
Definition at line 2096 of file robot_state.cpp.
|
inline |
Given a twist for a particular link (tip), compute the corresponding velocity for every variable and store it in qdot.
Definition at line 1249 of file robot_state.h.
void moveit::core::RobotState::computeVariableVelocity | ( | const JointModelGroup * | jmg, |
Eigen::VectorXd & | qdot, | ||
const Eigen::VectorXd & | twist, | ||
const LinkModel * | tip | ||
) | const |
Given a twist for a particular link (tip), compute the corresponding velocity for every variable and store it in qdot.
Definition at line 1498 of file robot_state.cpp.
|
private |
Definition at line 215 of file robot_state.cpp.
void moveit::core::RobotState::copyJointGroupAccelerations | ( | const JointModelGroup * | group, |
double * | gstate | ||
) | const |
For a given group, copy the acceleration values of the variables that make up the group into another location, in the order that the variables are found in the group. This is not necessarily a contiguous block of memory in the RobotState itself, so we copy instead of returning a pointer.
Definition at line 711 of file robot_state.cpp.
void moveit::core::RobotState::copyJointGroupAccelerations | ( | const JointModelGroup * | group, |
Eigen::VectorXd & | values | ||
) | const |
For a given group, copy the acceleration values of the variables that make up the group into another location, in the order that the variables are found in the group. This is not necessarily a contiguous block of memory in the RobotState itself, so we copy instead of returning a pointer.
Definition at line 721 of file robot_state.cpp.
|
inline |
For a given group, copy the acceleration values of the variables that make up the group into another location, in the order that the variables are found in the group. This is not necessarily a contiguous block of memory in the RobotState itself, so we copy instead of returning a pointer.
Definition at line 980 of file robot_state.h.
|
inline |
For a given group, copy the acceleration values of the variables that make up the group into another location, in the order that the variables are found in the group. This is not necessarily a contiguous block of memory in the RobotState itself, so we copy instead of returning a pointer.
Definition at line 970 of file robot_state.h.
|
inline |
For a given group, copy the acceleration values of the variables that make up the group into another location, in the order that the variables are found in the group. This is not necessarily a contiguous block of memory in the RobotState itself, so we copy instead of returning a pointer.
Definition at line 994 of file robot_state.h.
|
inline |
For a given group, copy the acceleration values of the variables that make up the group into another location, in the order that the variables are found in the group. This is not necessarily a contiguous block of memory in the RobotState itself, so we copy instead of returning a pointer.
Definition at line 957 of file robot_state.h.
void moveit::core::RobotState::copyJointGroupPositions | ( | const JointModelGroup * | group, |
double * | gstate | ||
) | const |
For a given group, copy the position values of the variables that make up the group into another location, in the order that the variables are found in the group. This is not necessarily a contiguous block of memory in the RobotState itself, so we copy instead of returning a pointer.
Definition at line 633 of file robot_state.cpp.
void moveit::core::RobotState::copyJointGroupPositions | ( | const JointModelGroup * | group, |
Eigen::VectorXd & | values | ||
) | const |
For a given group, copy the position values of the variables that make up the group into another location, in the order that the variables are found in the group. This is not necessarily a contiguous block of memory in the RobotState itself, so we copy instead of returning a pointer.
Definition at line 643 of file robot_state.cpp.
|
inline |
For a given group, copy the position values of the variables that make up the group into another location, in the order that the variables are found in the group. This is not necessarily a contiguous block of memory in the RobotState itself, so we copy instead of returning a pointer.
Definition at line 780 of file robot_state.h.
|
inline |
For a given group, copy the position values of the variables that make up the group into another location, in the order that the variables are found in the group. This is not necessarily a contiguous block of memory in the RobotState itself, so we copy instead of returning a pointer.
Definition at line 770 of file robot_state.h.
|
inline |
For a given group, copy the position values of the variables that make up the group into another location, in the order that the variables are found in the group. This is not necessarily a contiguous block of memory in the RobotState itself, so we copy instead of returning a pointer.
Definition at line 794 of file robot_state.h.
|
inline |
For a given group, copy the position values of the variables that make up the group into another location, in the order that the variables are found in the group. This is not necessarily a contiguous block of memory in the RobotState itself, so we copy instead of returning a pointer.
Definition at line 757 of file robot_state.h.
void moveit::core::RobotState::copyJointGroupVelocities | ( | const JointModelGroup * | group, |
double * | gstate | ||
) | const |
For a given group, copy the velocity values of the variables that make up the group into another location, in the order that the variables are found in the group. This is not necessarily a contiguous block of memory in the RobotState itself, so we copy instead of returning a pointer.
Definition at line 672 of file robot_state.cpp.
void moveit::core::RobotState::copyJointGroupVelocities | ( | const JointModelGroup * | group, |
Eigen::VectorXd & | values | ||
) | const |
For a given group, copy the velocity values of the variables that make up the group into another location, in the order that the variables are found in the group. This is not necessarily a contiguous block of memory in the RobotState itself, so we copy instead of returning a pointer.
Definition at line 682 of file robot_state.cpp.
|
inline |
For a given group, copy the velocity values of the variables that make up the group into another location, in the order that the variables are found in the group. This is not necessarily a contiguous block of memory in the RobotState itself, so we copy instead of returning a pointer.
Definition at line 880 of file robot_state.h.
|
inline |
For a given group, copy the velocity values of the variables that make up the group into another location, in the order that the variables are found in the group. This is not necessarily a contiguous block of memory in the RobotState itself, so we copy instead of returning a pointer.
Definition at line 870 of file robot_state.h.
|
inline |
For a given group, copy the velocity values of the variables that make up the group into another location, in the order that the variables are found in the group. This is not necessarily a contiguous block of memory in the RobotState itself, so we copy instead of returning a pointer.
Definition at line 894 of file robot_state.h.
|
inline |
For a given group, copy the velocity values of the variables that make up the group into another location, in the order that the variables are found in the group. This is not necessarily a contiguous block of memory in the RobotState itself, so we copy instead of returning a pointer.
Definition at line 857 of file robot_state.h.
|
inline |
Returns true if anything in this state is dirty.
Definition at line 1492 of file robot_state.h.
|
inline |
Definition at line 1486 of file robot_state.h.
|
inline |
Definition at line 1476 of file robot_state.h.
|
inline |
Definition at line 1481 of file robot_state.h.
|
inline |
Return the sum of joint distances to "other" state. Only considers active joints.
Definition at line 1504 of file robot_state.h.
|
inline |
Return the sum of joint distances to "other" state. Only considers active joints.
Definition at line 1513 of file robot_state.h.
double moveit::core::RobotState::distance | ( | const RobotState & | other, |
const JointModelGroup * | joint_group | ||
) | const |
Return the sum of joint distances to "other" state. Only considers active joints.
Definition at line 1032 of file robot_state.cpp.
void moveit::core::RobotState::dropAccelerations | ( | ) |
Remove accelerations from this state (this differs from setting them to zero)
Definition at line 336 of file robot_state.cpp.
void moveit::core::RobotState::dropDynamics | ( | ) |
Reduce RobotState to kinematic information (remove velocity, acceleration and effort, if present)
Definition at line 346 of file robot_state.cpp.
void moveit::core::RobotState::dropEffort | ( | ) |
Remove effort values from this state (this differs from setting them to zero)
Definition at line 341 of file robot_state.cpp.
void moveit::core::RobotState::dropVelocities | ( | ) |
Remove velocities from this state (this differs from setting them to zero)
Definition at line 331 of file robot_state.cpp.
void moveit::core::RobotState::enforceBounds | ( | ) |
Definition at line 939 of file robot_state.cpp.
|
inline |
Definition at line 1559 of file robot_state.h.
void moveit::core::RobotState::enforceBounds | ( | const JointModelGroup * | joint_group | ) |
Definition at line 946 of file robot_state.cpp.
|
inline |
Definition at line 1565 of file robot_state.h.
|
inline |
Definition at line 1584 of file robot_state.h.
void moveit::core::RobotState::getAttachedBodies | ( | std::vector< const AttachedBody * > & | attached_bodies | ) | const |
Get all bodies attached to the model corresponding to this state.
Definition at line 1113 of file robot_state.cpp.
void moveit::core::RobotState::getAttachedBodies | ( | std::vector< const AttachedBody * > & | attached_bodies, |
const JointModelGroup * | group | ||
) | const |
Get all bodies attached to a particular group the model corresponding to this state.
Definition at line 1121 of file robot_state.cpp.
void moveit::core::RobotState::getAttachedBodies | ( | std::vector< const AttachedBody * > & | attached_bodies, |
const LinkModel * | link_model | ||
) | const |
Get all bodies attached to a particular link in the model corresponding to this state.
Definition at line 1129 of file robot_state.cpp.
const AttachedBody * moveit::core::RobotState::getAttachedBody | ( | const std::string & | name | ) | const |
Get the attached body named name. Return NULL if not found.
Definition at line 1075 of file robot_state.cpp.
|
inline |
Definition at line 1431 of file robot_state.h.
|
inline |
Definition at line 1442 of file robot_state.h.
|
inline |
Get the link transform w.r.t. the root link (model frame) of the RobotModel. This is typically the root link of the URDF unless a virtual joint is present. Checks the cache and if there are any dirty (non-updated) transforms, first updates them as needed.
As opposed to the visual links in |getGlobalLinkTransform|, this function returns the collision link transform used for collision checking.
link_name | name of link to lookup |
index | specify which collision body to lookup, if more than one exists |
Definition at line 1426 of file robot_state.h.
|
inline |
Definition at line 1437 of file robot_state.h.
const Eigen::Isometry3d & moveit::core::RobotState::getFrameInfo | ( | const std::string & | frame_id, |
const LinkModel *& | robot_link, | ||
bool & | frame_found | ||
) | const |
Get the transformation matrix from the model frame (root of model) to the frame identified by frame_id.
If this frame is attached to a robot link, the link pointer is returned in robot_link. If frame_id was not found, frame_found is set to false and an identity transform is returned.
The returned transformation is always a valid isometry.
Definition at line 1211 of file robot_state.cpp.
const Eigen::Isometry3d & moveit::core::RobotState::getFrameTransform | ( | const std::string & | frame_id, |
bool * | frame_found = nullptr |
||
) |
Get the transformation matrix from the model frame (root of model) to the frame identified by frame_id.
If frame_id was not found, frame_found is set to false and an identity transform is returned.
The returned transformation is always a valid isometry.
Definition at line 1191 of file robot_state.cpp.
const Eigen::Isometry3d & moveit::core::RobotState::getFrameTransform | ( | const std::string & | frame_id, |
bool * | frame_found = nullptr |
||
) | const |
Get the transformation matrix from the model frame (root of model) to the frame identified by frame_id.
If frame_id was not found, frame_found is set to false and an identity transform is returned.
The returned transformation is always a valid isometry.
Definition at line 1197 of file robot_state.cpp.
|
inline |
Definition at line 1399 of file robot_state.h.
|
inline |
Definition at line 1410 of file robot_state.h.
|
inline |
Get the link transform w.r.t. the root link (model frame) of the RobotModel. This is typically the root link of the URDF unless a virtual joint is present. Checks the cache and if there are any dirty (non-updated) transforms, first updates them as needed. A related, more comprehensive function is |getFrameTransform|, which additionally to link frames also searches for attached object frames and their subframes.
The returned transformation is always a valid isometry.
Definition at line 1394 of file robot_state.h.
|
inline |
Definition at line 1405 of file robot_state.h.
|
inline |
Compute the Jacobian with reference to the last link of a specified group. If the group is not a chain, an exception is thrown.
group | The group to compute the Jacobian for |
reference_point_position | The reference point position (with respect to the link specified in link_name) |
Definition at line 1235 of file robot_state.h.
Eigen::MatrixXd moveit::core::RobotState::getJacobian | ( | const JointModelGroup * | group, |
const Eigen::Vector3d & | reference_point_position = Eigen::Vector3d(0.0, 0.0, 0.0) |
||
) | const |
Compute the Jacobian with reference to the last link of a specified group. If the group is not a chain, an exception is thrown.
group | The group to compute the Jacobian for |
reference_point_position | The reference point position (with respect to the link specified in link_name) |
Definition at line 1365 of file robot_state.cpp.
|
inline |
Compute the Jacobian with reference to a particular point on a given link, for a specified group.
group | The group to compute the Jacobian for |
link | The link model to compute the Jacobian for |
reference_point_position | The reference point position (with respect to the link specified in link) |
jacobian | The resultant jacobian |
use_quaternion_representation | Flag indicating if the Jacobian should use a quaternion representation (default is false) |
Definition at line 1212 of file robot_state.h.
bool moveit::core::RobotState::getJacobian | ( | const JointModelGroup * | group, |
const LinkModel * | link, | ||
const Eigen::Vector3d & | reference_point_position, | ||
Eigen::MatrixXd & | jacobian, | ||
bool | use_quaternion_representation = false |
||
) | const |
Compute the Jacobian with reference to a particular point on a given link, for a specified group.
group | The group to compute the Jacobian for |
link | The link model to compute the Jacobian for |
reference_point_position | The reference point position (with respect to the link specified in link) |
jacobian | The resultant jacobian |
use_quaternion_representation | Flag indicating if the Jacobian should use a quaternion representation (default is false) |
Definition at line 1374 of file robot_state.cpp.
|
inline |
Definition at line 648 of file robot_state.h.
|
inline |
Definition at line 643 of file robot_state.h.
|
inline |
Definition at line 658 of file robot_state.h.
|
inline |
Definition at line 653 of file robot_state.h.
|
inline |
Get the model of a particular joint.
Definition at line 194 of file robot_state.h.
|
inline |
Get the model of a particular joint group.
Definition at line 200 of file robot_state.h.
|
inline |
Definition at line 628 of file robot_state.h.
|
inline |
Definition at line 623 of file robot_state.h.
|
inline |
Definition at line 1453 of file robot_state.h.
|
inline |
Definition at line 1470 of file robot_state.h.
|
inline |
Definition at line 1448 of file robot_state.h.
|
inline |
Definition at line 1465 of file robot_state.h.
|
inline |
Definition at line 638 of file robot_state.h.
|
inline |
Definition at line 633 of file robot_state.h.
|
inline |
Get the model of a particular link.
Definition at line 188 of file robot_state.h.
std::pair< double, const JointModel * > moveit::core::RobotState::getMinDistanceToPositionBounds | ( | ) | const |
Get the minimm distance from this state to the bounds. The minimum distance and the joint for which this minimum is achieved are returned.
Definition at line 965 of file robot_state.cpp.
std::pair< double, const JointModel * > moveit::core::RobotState::getMinDistanceToPositionBounds | ( | const JointModelGroup * | group | ) | const |
Get the minimm distance from a group in this state to the bounds. The minimum distance and the joint for which this minimum is achieved are returned.
Definition at line 970 of file robot_state.cpp.
std::pair< double, const JointModel * > moveit::core::RobotState::getMinDistanceToPositionBounds | ( | const std::vector< const JointModel * > & | joints | ) | const |
Get the minimm distance from a set of joints in the state to the bounds. The minimum distance and the joint for which this minimum is achieved are returned.
Definition at line 976 of file robot_state.cpp.
|
private |
Definition at line 467 of file robot_state.cpp.
|
inline |
Return the instance of a random number generator.
Definition at line 1758 of file robot_state.h.
const LinkModel * moveit::core::RobotState::getRigidlyConnectedParentLinkModel | ( | const std::string & | frame, |
Eigen::Isometry3d * | transform = nullptr , |
||
const moveit::core::JointModelGroup * | jmg = nullptr |
||
) | const |
Get the latest link upwards the kinematic tree which is only connected via fixed joints.
This behaves the same as RobotModel::getRigidlyConnectedParentLinkModel, but can additionally resolve parents for attached objects / subframes.
If transform is specified, return the (fixed) relative transform from the returned parent link to frame.
Definition at line 875 of file robot_state.cpp.
|
inline |
Get a MarkerArray that fully describes the robot markers for a given robot. Update the state first.
arr | The returned marker array |
link_names | The list of link names for which the markers should be created. |
Definition at line 1828 of file robot_state.h.
void moveit::core::RobotState::getRobotMarkers | ( | visualization_msgs::MarkerArray & | arr, |
const std::vector< std::string > & | link_names, | ||
bool | include_attached = false |
||
) | const |
Get a MarkerArray that fully describes the robot markers for a given robot.
arr | The returned marker array |
link_names | The list of link names for which the markers should be created. |
Definition at line 1296 of file robot_state.cpp.
|
inline |
Get a MarkerArray that fully describes the robot markers for a given robot. Update the state first.
arr | The returned marker array |
link_names | The list of link names for which the markers should be created. |
color | The color for the marker |
ns | The namespace for the markers |
dur | The ros::Duration for which the markers should stay visible |
Definition at line 1809 of file robot_state.h.
void moveit::core::RobotState::getRobotMarkers | ( | visualization_msgs::MarkerArray & | arr, |
const std::vector< std::string > & | link_names, | ||
const std_msgs::ColorRGBA & | color, | ||
const std::string & | ns, | ||
const ros::Duration & | dur, | ||
bool | include_attached = false |
||
) | const |
Get a MarkerArray that fully describes the robot markers for a given robot.
arr | The returned marker array |
link_names | The list of link names for which the markers should be created. |
color | The color for the marker |
ns | The namespace for the markers |
dur | The ros::Duration for which the markers should stay visible |
Definition at line 1280 of file robot_state.cpp.
|
inline |
Get the robot model this state is constructed for.
Definition at line 170 of file robot_state.h.
|
private |
Definition at line 2321 of file robot_state.cpp.
std::string moveit::core::RobotState::getStateTreeString | ( | ) | const |
Definition at line 2296 of file robot_state.cpp.
|
inline |
Get the acceleration of a particular variable. An exception is thrown if the variable is not known.
Definition at line 461 of file robot_state.h.
|
inline |
Get the acceleration of a particular variable. The variable is specified by its index. No checks are performed for the validity of the index passed
Definition at line 469 of file robot_state.h.
|
inline |
Get raw access to the accelerations of the variables that make up this state. The values are in the same order as reported by getVariableNames(). The area of memory overlaps with effort (effort and acceleration should not be set at the same time)
Definition at line 396 of file robot_state.h.
|
inline |
Get const raw access to the accelerations of the variables that make up this state. The values are in the same order as reported by getVariableNames()
Definition at line 404 of file robot_state.h.
|
inline |
Get the number of variables that make up this state.
Definition at line 176 of file robot_state.h.
|
inline |
Get raw access to the effort of the variables that make up this state. The values are in the same order as reported by getVariableNames(). The area of memory overlaps with accelerations (effort and acceleration should not be set at the same time)
Definition at line 494 of file robot_state.h.
|
inline |
Get const raw access to the effort of the variables that make up this state. The values are in the same order as reported by getVariableNames().
Definition at line 502 of file robot_state.h.
|
inline |
Get the effort of a particular variable. An exception is thrown if the variable is not known.
Definition at line 552 of file robot_state.h.
|
inline |
Get the effort of a particular variable. The variable is specified by its index. No checks are performed for the validity of the index passed
Definition at line 560 of file robot_state.h.
|
inline |
Get the names of the variables that make up this state, in the order they are stored in memory.
Definition at line 182 of file robot_state.h.
|
inline |
Get the position of a particular variable. An exception is thrown if the variable is not known.
Definition at line 273 of file robot_state.h.
|
inline |
Get the position of a particular variable. The variable is specified by its index. No checks are performed for the validity of the index passed
Definition at line 281 of file robot_state.h.
|
inline |
Get a raw pointer to the positions of the variables stored in this state. Use carefully. If you change these values externally you need to make sure you trigger a forced update for the state by calling update(true).
Definition at line 213 of file robot_state.h.
|
inline |
Get a raw pointer to the positions of the variables stored in this state.
Definition at line 220 of file robot_state.h.
|
inline |
Get raw access to the velocities of the variables that make up this state. The values are in the same order as reported by getVariableNames()
Definition at line 302 of file robot_state.h.
|
inline |
Get const access to the velocities of the variables that make up this state. The values are in the same order as reported by getVariableNames()
Definition at line 310 of file robot_state.h.
|
inline |
Get the velocity of a particular variable. An exception is thrown if the variable is not known.
Definition at line 362 of file robot_state.h.
|
inline |
Get the velocity of a particular variable. The variable is specified by its index. No checks are performed for the validity of the index passed
Definition at line 370 of file robot_state.h.
|
inline |
Definition at line 1577 of file robot_state.h.
void moveit::core::RobotState::harmonizePositions | ( | ) |
Call harmonizePosition() for all joints / all joints in group / given joint.
Definition at line 953 of file robot_state.cpp.
void moveit::core::RobotState::harmonizePositions | ( | const JointModelGroup * | joint_group | ) |
Definition at line 959 of file robot_state.cpp.
|
inline |
By default, if accelerations are never set or initialized, the state remembers that there are no accelerations set. This is useful to know when serializing or copying the state. If hasAccelerations() reports true, hasEffort() will certainly report false.
Definition at line 388 of file robot_state.h.
bool moveit::core::RobotState::hasAttachedBody | ( | const std::string & | id | ) | const |
Check if an attached body named id exists in this state.
Definition at line 1070 of file robot_state.cpp.
|
inline |
By default, if effort is never set or initialized, the state remembers that there is no effort set. This is useful to know when serializing or copying the state. If hasEffort() reports true, hasAccelerations() will certainly report false.
Definition at line 486 of file robot_state.h.
|
inline |
By default, if velocities are never set or initialized, the state remembers that there are no velocities set. This is useful to know when serializing or copying the state.
Definition at line 295 of file robot_state.h.
|
private |
Definition at line 189 of file robot_state.cpp.
bool moveit::core::RobotState::integrateVariableVelocity | ( | const JointModelGroup * | jmg, |
const Eigen::VectorXd & | qdot, | ||
double | dt, | ||
const GroupStateValidityCallbackFn & | constraint = GroupStateValidityCallbackFn() |
||
) |
Given the velocities for the variables in this group (qdot) and an amount of time (dt), update the current state using the Euler forward method. If the constraint specified is satisfied, return true, otherwise return false.
Definition at line 1539 of file robot_state.cpp.
void moveit::core::RobotState::interpolate | ( | const RobotState & | to, |
double | t, | ||
RobotState & | state | ||
) | const |
Interpolate towards "to" state. Mimic joints are correctly updated and flags are set so that FK is recomputed when needed.
to | interpolate to this state |
t | a fraction in the range [0 1]. If 1, the result matches "to" state exactly. |
state | holds the result |
Definition at line 1044 of file robot_state.cpp.
|
inline |
Interpolate towards "to" state, but only for a single joint. Mimic joints are correctly updated and flags are set so that FK is recomputed when needed.
to | interpolate to this state |
t | a fraction in the range [0 1]. If 1, the result matches "to" state exactly. |
state | holds the result |
joint | interpolate only for this joint |
Definition at line 1549 of file robot_state.h.
void moveit::core::RobotState::interpolate | ( | const RobotState & | to, |
double | t, | ||
RobotState & | state, | ||
const JointModelGroup * | joint_group | ||
) | const |
Interpolate towards "to" state, but only for the joints in the specified group. Mimic joints are correctly updated and flags are set so that FK is recomputed when needed.
to | interpolate to this state |
t | a fraction in the range [0 1]. If 1, the result matches "to" state exactly. |
state | holds the result |
joint_group | interpolate only for the joints in this group |
Definition at line 1053 of file robot_state.cpp.
void moveit::core::RobotState::invertVelocity | ( | ) |
Invert velocity if present.
Definition at line 567 of file robot_state.cpp.
bool moveit::core::RobotState::isValidVelocityMove | ( | const RobotState & | other, |
const JointModelGroup * | group, | ||
double | dt | ||
) | const |
Check that the time to move between two waypoints is sufficient given velocity limits and time step.
other | - robot state to compare joint positions against |
group | - planning group to compare joint positions against |
dt | - time step between the two points |
Definition at line 1012 of file robot_state.cpp.
bool moveit::core::RobotState::knowsFrameTransform | ( | const std::string & | frame_id | ) | const |
Check if a transformation matrix from the model frame (root of model) to frame frame_id is known.
Definition at line 1259 of file robot_state.cpp.
|
private |
Definition at line 293 of file robot_state.cpp.
|
inlineprivate |
Definition at line 1871 of file robot_state.h.
|
inlineprivate |
Definition at line 1878 of file robot_state.h.
|
private |
Definition at line 303 of file robot_state.cpp.
|
private |
Definition at line 284 of file robot_state.cpp.
RobotState & moveit::core::RobotState::operator= | ( | const RobotState & | other | ) |
Copy operator.
Definition at line 208 of file robot_state.cpp.
void moveit::core::RobotState::printDirtyInfo | ( | std::ostream & | out = std::cout | ) | const |
Definition at line 2190 of file robot_state.cpp.
void moveit::core::RobotState::printStateInfo | ( | std::ostream & | out = std::cout | ) | const |
Definition at line 2203 of file robot_state.cpp.
void moveit::core::RobotState::printStatePositions | ( | std::ostream & | out = std::cout | ) | const |
Definition at line 2131 of file robot_state.cpp.
void moveit::core::RobotState::printStatePositionsWithJointLimits | ( | const moveit::core::JointModelGroup * | jmg, |
std::ostream & | out = std::cout |
||
) | const |
Output to console the current state of the robot's joint limits.
Definition at line 2138 of file robot_state.cpp.
void moveit::core::RobotState::printTransform | ( | const Eigen::Isometry3d & | transform, |
std::ostream & | out = std::cout |
||
) | const |
Definition at line 2246 of file robot_state.cpp.
void moveit::core::RobotState::printTransforms | ( | std::ostream & | out = std::cout | ) | const |
Definition at line 2264 of file robot_state.cpp.
|
inline |
Definition at line 1591 of file robot_state.h.
bool moveit::core::RobotState::satisfiesBounds | ( | const JointModelGroup * | joint_group, |
double | margin = 0.0 |
||
) | const |
Definition at line 930 of file robot_state.cpp.
bool moveit::core::RobotState::satisfiesBounds | ( | double | margin = 0.0 | ) | const |
Definition at line 921 of file robot_state.cpp.
|
inline |
Definition at line 1595 of file robot_state.h.
|
inline |
Definition at line 1599 of file robot_state.h.
void moveit::core::RobotState::setAttachedBodyUpdateCallback | ( | const AttachedBodyCallback & | callback | ) |
Definition at line 1065 of file robot_state.cpp.
bool moveit::core::RobotState::setFromDiffIK | ( | const JointModelGroup * | group, |
const Eigen::VectorXd & | twist, | ||
const std::string & | tip, | ||
double | dt, | ||
const GroupStateValidityCallbackFn & | constraint = GroupStateValidityCallbackFn() |
||
) |
Set the joint values from a Cartesian velocity applied during a time dt.
group | the group of joints this function operates on |
twist | a Cartesian velocity on the 'tip' frame |
tip | the frame for which the twist is given |
dt | a time interval (seconds) |
Definition at line 1482 of file robot_state.cpp.
bool moveit::core::RobotState::setFromDiffIK | ( | const JointModelGroup * | group, |
const geometry_msgs::Twist & | twist, | ||
const std::string & | tip, | ||
double | dt, | ||
const GroupStateValidityCallbackFn & | constraint = GroupStateValidityCallbackFn() |
||
) |
Set the joint values from a Cartesian velocity applied during a time dt.
group | the group of joints this function operates on |
twist | a Cartesian velocity on the 'tip' frame |
tip | the frame for which the twist is given |
dt | a time interval (seconds) |
Definition at line 1490 of file robot_state.cpp.
bool moveit::core::RobotState::setFromIK | ( | const JointModelGroup * | group, |
const Eigen::Isometry3d & | pose, | ||
const std::string & | tip, | ||
const std::vector< double > & | consistency_limits, | ||
double | timeout = 0.0 , |
||
const GroupStateValidityCallbackFn & | constraint = GroupStateValidityCallbackFn() , |
||
const kinematics::KinematicsQueryOptions & | options = kinematics::KinematicsQueryOptions() |
||
) |
If the group this state corresponds to is a chain and a solver is available, then the joint values can be set by computing inverse kinematics. The pose is assumed to be in the reference frame of the kinematic model. Returns true on success.
pose | The pose the last link in the chain needs to achieve |
tip | The name of the frame for which IK is attempted. |
consistency_limits | This specifies the desired distance between the solution and the seed state |
timeout | The timeout passed to the kinematics solver on each attempt |
constraint | A state validity constraint to be required for IK solutions |
Definition at line 1642 of file robot_state.cpp.
|
inline |
Definition at line 1096 of file robot_state.h.
bool moveit::core::RobotState::setFromIK | ( | const JointModelGroup * | group, |
const Eigen::Isometry3d & | pose, | ||
const std::string & | tip, | ||
double | timeout = 0.0 , |
||
const GroupStateValidityCallbackFn & | constraint = GroupStateValidityCallbackFn() , |
||
const kinematics::KinematicsQueryOptions & | options = kinematics::KinematicsQueryOptions() |
||
) |
If the group this state corresponds to is a chain and a solver is available, then the joint values can be set by computing inverse kinematics. The pose is assumed to be in the reference frame of the kinematic model. Returns true on success.
pose | The pose the last link in the chain needs to achieve |
timeout | The timeout passed to the kinematics solver on each attempt |
constraint | A state validity constraint to be required for IK solutions |
Definition at line 1595 of file robot_state.cpp.
|
inline |
Definition at line 1075 of file robot_state.h.
bool moveit::core::RobotState::setFromIK | ( | const JointModelGroup * | group, |
const Eigen::Isometry3d & | pose, | ||
double | timeout = 0.0 , |
||
const GroupStateValidityCallbackFn & | constraint = GroupStateValidityCallbackFn() , |
||
const kinematics::KinematicsQueryOptions & | options = kinematics::KinematicsQueryOptions() |
||
) |
If the group this state corresponds to is a chain and a solver is available, then the joint values can be set by computing inverse kinematics. The pose is assumed to be in the reference frame of the kinematic model. Returns true on success.
pose | The pose the last link in the chain needs to achieve |
tip | The name of the link the pose is specified for |
timeout | The timeout passed to the kinematics solver on each attempt |
Definition at line 1581 of file robot_state.cpp.
|
inline |
Definition at line 1058 of file robot_state.h.
bool moveit::core::RobotState::setFromIK | ( | const JointModelGroup * | group, |
const EigenSTL::vector_Isometry3d & | poses, | ||
const std::vector< std::string > & | tips, | ||
const std::vector< std::vector< double >> & | consistency_limits, | ||
double | timeout = 0.0 , |
||
const GroupStateValidityCallbackFn & | constraint = GroupStateValidityCallbackFn() , |
||
const kinematics::KinematicsQueryOptions & | options = kinematics::KinematicsQueryOptions() |
||
) |
Warning: This function inefficiently copies all transforms around. If the group consists of a set of sub-groups that are each a chain and a solver is available for each sub-group, then the joint values can be set by computing inverse kinematics. The poses are assumed to be in the reference frame of the kinematic model. The poses are assumed to be in the same order as the order of the sub-groups in this group. Returns true on success.
poses | The poses the last link in each chain needs to achieve |
tips | The names of the frames for which IK is attempted. |
consistency_limits | This specifies the desired distance between the solution and the seed state |
timeout | The timeout passed to the kinematics solver on each attempt |
constraint | A state validity constraint to be required for IK solutions |
|
inline |
Definition at line 1141 of file robot_state.h.
bool moveit::core::RobotState::setFromIK | ( | const JointModelGroup * | group, |
const EigenSTL::vector_Isometry3d & | poses, | ||
const std::vector< std::string > & | tips, | ||
double | timeout = 0.0 , |
||
const GroupStateValidityCallbackFn & | constraint = GroupStateValidityCallbackFn() , |
||
const kinematics::KinematicsQueryOptions & | options = kinematics::KinematicsQueryOptions() |
||
) |
Warning: This function inefficiently copies all transforms around. If the group consists of a set of sub-groups that are each a chain and a solver is available for each sub-group, then the joint values can be set by computing inverse kinematics. The poses are assumed to be in the reference frame of the kinematic model. The poses are assumed to be in the same order as the order of the sub-groups in this group. Returns true on success.
poses | The poses the last link in each chain needs to achieve |
tips | The names of the frames for which IK is attempted. |
timeout | The timeout passed to the kinematics solver on each attempt |
constraint | A state validity constraint to be required for IK solutions |
Definition at line 1660 of file robot_state.cpp.
|
inline |
Definition at line 1118 of file robot_state.h.
bool moveit::core::RobotState::setFromIK | ( | const JointModelGroup * | group, |
const geometry_msgs::Pose & | pose, | ||
const std::string & | tip, | ||
double | timeout = 0.0 , |
||
const GroupStateValidityCallbackFn & | constraint = GroupStateValidityCallbackFn() , |
||
const kinematics::KinematicsQueryOptions & | options = kinematics::KinematicsQueryOptions() |
||
) |
If the group this state corresponds to is a chain and a solver is available, then the joint values can be set by computing inverse kinematics. The pose is assumed to be in the reference frame of the kinematic model. Returns true on success.
pose | The pose the tip link in the chain needs to achieve |
tip | The name of the link the pose is specified for |
timeout | The timeout passed to the kinematics solver on each attempt |
constraint | A state validity constraint to be required for IK solutions |
Definition at line 1571 of file robot_state.cpp.
|
inline |
Definition at line 1040 of file robot_state.h.
bool moveit::core::RobotState::setFromIK | ( | const JointModelGroup * | group, |
const geometry_msgs::Pose & | pose, | ||
double | timeout = 0.0 , |
||
const GroupStateValidityCallbackFn & | constraint = GroupStateValidityCallbackFn() , |
||
const kinematics::KinematicsQueryOptions & | options = kinematics::KinematicsQueryOptions() |
||
) |
If the group this state corresponds to is a chain and a solver is available, then the joint values can be set by computing inverse kinematics. The pose is assumed to be in the reference frame of the kinematic model. Returns true on success.
pose | The pose the last link in the chain needs to achieve |
timeout | The timeout passed to the kinematics solver on each attempt |
constraint | A state validity constraint to be required for IK solutions |
Definition at line 1558 of file robot_state.cpp.
|
inline |
Definition at line 1022 of file robot_state.h.
bool moveit::core::RobotState::setFromIKSubgroups | ( | const JointModelGroup * | group, |
const EigenSTL::vector_Isometry3d & | poses, | ||
const std::vector< std::string > & | tips, | ||
const std::vector< std::vector< double >> & | consistency_limits, | ||
double | timeout = 0.0 , |
||
const GroupStateValidityCallbackFn & | constraint = GroupStateValidityCallbackFn() , |
||
const kinematics::KinematicsQueryOptions & | options = kinematics::KinematicsQueryOptions() |
||
) |
setFromIK for multiple poses and tips (end effectors) when no solver exists for the jmg that can solver for non-chain kinematics. In this case, we divide the group into subgroups and do IK solving individually
poses | The poses the last link in each chain needs to achieve |
tips | The names of the frames for which IK is attempted. |
consistency_limits | This specifies the desired distance between the solution and the seed state |
timeout | The timeout passed to the kinematics solver on each attempt |
constraint | A state validity constraint to be required for IK solutions |
|
inline |
Definition at line 1164 of file robot_state.h.
void moveit::core::RobotState::setJointEfforts | ( | const JointModel * | joint, |
const double * | effort | ||
) |
Definition at line 576 of file robot_state.cpp.
void moveit::core::RobotState::setJointGroupAccelerations | ( | const JointModelGroup * | group, |
const double * | gstate | ||
) |
Given accelerations for the variables that make up a group, in the order found in the group (including values of mimic joints), set those as the new values that correspond to the group.
Definition at line 690 of file robot_state.cpp.
void moveit::core::RobotState::setJointGroupAccelerations | ( | const JointModelGroup * | group, |
const Eigen::VectorXd & | values | ||
) |
Given accelerations for the variables that make up a group, in the order found in the group (including values of mimic joints), set those as the new values that correspond to the group.
Definition at line 703 of file robot_state.cpp.
|
inline |
Given accelerations for the variables that make up a group, in the order found in the group (including values of mimic joints), set those as the new values that correspond to the group.
Definition at line 932 of file robot_state.h.
|
inline |
Given accelerations for the variables that make up a group, in the order found in the group (including values of mimic joints), set those as the new values that correspond to the group.
Definition at line 914 of file robot_state.h.
|
inline |
Given accelerations for the variables that make up a group, in the order found in the group (including values of mimic joints), set those as the new values that correspond to the group.
Definition at line 943 of file robot_state.h.
|
inline |
Given accelerations for the variables that make up a group, in the order found in the group (including values of mimic joints), set those as the new values that correspond to the group.
Definition at line 923 of file robot_state.h.
void moveit::core::RobotState::setJointGroupActivePositions | ( | const JointModelGroup * | group, |
const Eigen::VectorXd & | values | ||
) |
Given positions for the variables of active joints that make up a group, in the order found in the group (excluding values of mimic joints), set those as the new values that correspond to the group.
Definition at line 621 of file robot_state.cpp.
void moveit::core::RobotState::setJointGroupActivePositions | ( | const JointModelGroup * | group, |
const std::vector< double > & | gstate | ||
) |
Given positions for the variables of active joints that make up a group, in the order found in the group (excluding values of mimic joints), set those as the new values that correspond to the group.
Definition at line 609 of file robot_state.cpp.
|
inline |
Given positions for the variables of active joints that make up a group, in the order found in the group (excluding values of mimic joints), set those as the new values that correspond to the group.
Definition at line 744 of file robot_state.h.
|
inline |
Given positions for the variables of active joints that make up a group, in the order found in the group (excluding values of mimic joints), set those as the new values that correspond to the group.
Definition at line 726 of file robot_state.h.
void moveit::core::RobotState::setJointGroupPositions | ( | const JointModelGroup * | group, |
const double * | gstate | ||
) |
Given positions for the variables that make up a group, in the order found in the group (including values of mimic joints), set those as the new values that correspond to the group.
Definition at line 588 of file robot_state.cpp.
void moveit::core::RobotState::setJointGroupPositions | ( | const JointModelGroup * | group, |
const Eigen::VectorXd & | values | ||
) |
Given positions for the variables that make up a group, in the order found in the group (including values of mimic joints), set those as the new values that correspond to the group.
Definition at line 601 of file robot_state.cpp.
|
inline |
Given positions for the variables that make up a group, in the order found in the group (including values of mimic joints), set those as the new values that correspond to the group.
Definition at line 692 of file robot_state.h.
|
inline |
Given positions for the variables that make up a group, in the order found in the group (including values of mimic joints), set those as the new values that correspond to the group.
Definition at line 671 of file robot_state.h.
|
inline |
Given positions for the variables that make up a group, in the order found in the group (including values of mimic joints), set those as the new values that correspond to the group.
Definition at line 704 of file robot_state.h.
|
inline |
Given positions for the variables that make up a group, in the order found in the group (including values of mimic joints), set those as the new values that correspond to the group.
Definition at line 680 of file robot_state.h.
void moveit::core::RobotState::setJointGroupVelocities | ( | const JointModelGroup * | group, |
const double * | gstate | ||
) |
Given velocities for the variables that make up a group, in the order found in the group (including values of mimic joints), set those as the new values that correspond to the group.
Definition at line 651 of file robot_state.cpp.
void moveit::core::RobotState::setJointGroupVelocities | ( | const JointModelGroup * | group, |
const Eigen::VectorXd & | values | ||
) |
Given velocities for the variables that make up a group, in the order found in the group (including values of mimic joints), set those as the new values that correspond to the group.
Definition at line 664 of file robot_state.cpp.
|
inline |
Given velocities for the variables that make up a group, in the order found in the group (including values of mimic joints), set those as the new values that correspond to the group.
Definition at line 832 of file robot_state.h.
|
inline |
Given velocities for the variables that make up a group, in the order found in the group (including values of mimic joints), set those as the new values that correspond to the group.
Definition at line 814 of file robot_state.h.
|
inline |
Given velocities for the variables that make up a group, in the order found in the group (including values of mimic joints), set those as the new values that correspond to the group.
Definition at line 843 of file robot_state.h.
|
inline |
Given velocities for the variables that make up a group, in the order found in the group (including values of mimic joints), set those as the new values that correspond to the group.
Definition at line 823 of file robot_state.h.
|
inline |
Definition at line 596 of file robot_state.h.
|
inline |
Definition at line 608 of file robot_state.h.
|
inline |
Definition at line 591 of file robot_state.h.
|
inline |
Definition at line 581 of file robot_state.h.
|
inline |
Definition at line 603 of file robot_state.h.
|
inline |
Definition at line 586 of file robot_state.h.
|
inline |
Definition at line 615 of file robot_state.h.
void moveit::core::RobotState::setToDefaultValues | ( | ) |
Set all joints to their default positions. The default position is 0, or if that is not within bounds then half way between min and max bound.
Definition at line 434 of file robot_state.cpp.
bool moveit::core::RobotState::setToDefaultValues | ( | const JointModelGroup * | group, |
const std::string & | name | ||
) |
Set the joints in group to the position name defined in the SRDF.
Definition at line 426 of file robot_state.cpp.
|
inline |
Definition at line 1284 of file robot_state.h.
bool moveit::core::RobotState::setToIKSolverFrame | ( | Eigen::Isometry3d & | pose, |
const kinematics::KinematicsBaseConstPtr & | solver | ||
) |
Transform pose from the robot model's base frame to the reference frame of the IK solver.
pose | - the input to change |
solver | - a kin solver whose base frame is important to us |
Definition at line 1620 of file robot_state.cpp.
bool moveit::core::RobotState::setToIKSolverFrame | ( | Eigen::Isometry3d & | pose, |
const std::string & | ik_frame | ||
) |
Transform pose from the robot model's base frame to the reference frame of the IK solver.
pose | - the input to change |
ik_frame | - the name of frame of reference of base of ik solver |
Definition at line 1625 of file robot_state.cpp.
void moveit::core::RobotState::setToRandomPositions | ( | ) |
Set all joints to random values. Values will be within default bounds.
Definition at line 353 of file robot_state.cpp.
void moveit::core::RobotState::setToRandomPositions | ( | const JointModelGroup * | group | ) |
Set all joints in group to random values. Values will be within default bounds.
Definition at line 366 of file robot_state.cpp.
void moveit::core::RobotState::setToRandomPositions | ( | const JointModelGroup * | group, |
random_numbers::RandomNumberGenerator & | rng | ||
) |
Set all joints in group to random values using a specified random number generator. Values will be within default bounds.
Definition at line 373 of file robot_state.cpp.
void moveit::core::RobotState::setToRandomPositions | ( | random_numbers::RandomNumberGenerator & | rng | ) |
Set all joints to random values using the specified random number generator. Values will be within default bounds.
Definition at line 358 of file robot_state.cpp.
void moveit::core::RobotState::setToRandomPositionsNearBy | ( | const JointModelGroup * | group, |
const RobotState & | seed, | ||
const std::vector< double > & | distances | ||
) |
Set all joints in group to random values near the value in seed. distances MUST have the same size as group.getActiveJointModels()
. Each value in distances is the maximum amount the corresponding active joint in group will vary from the corresponding value in seed. distance represents meters for prismatic/postitional joints and radians for revolute/orientation joints. Resulting values are clamped within default bounds.
Definition at line 381 of file robot_state.cpp.
void moveit::core::RobotState::setToRandomPositionsNearBy | ( | const JointModelGroup * | group, |
const RobotState & | seed, | ||
const std::vector< double > & | distances, | ||
random_numbers::RandomNumberGenerator & | rng | ||
) |
Set all joints in group to random values near the value in seed, using a specified random number generator. distances MUST have the same size as group.getActiveJointModels()
. Each value in distances is the maximum amount the corresponding active joint in group will vary from the corresponding value in seed. distance represents meters for prismatic/postitional joints and radians for revolute/orientation joints. Resulting values are clamped within default bounds.
Definition at line 390 of file robot_state.cpp.
void moveit::core::RobotState::setToRandomPositionsNearBy | ( | const JointModelGroup * | group, |
const RobotState & | seed, | ||
double | distance | ||
) |
Set all joints in group to random values near the value in seed. distance is the maximum amount each joint value will vary from the corresponding value in seed. distance represents meters for prismatic/postitional joints and radians for revolute/orientation joints. Resulting values are clamped within default bounds.
Definition at line 405 of file robot_state.cpp.
void moveit::core::RobotState::setToRandomPositionsNearBy | ( | const JointModelGroup * | group, |
const RobotState & | seed, | ||
double | distance, | ||
random_numbers::RandomNumberGenerator & | rng | ||
) |
Set all joints in group to random values near the value in seed, using a specified random number generator. distance is the maximum amount each joint value will vary from the corresponding value in seed. distance represents meters for prismatic/postitional joints and radians for revolute/orientation joints. Resulting values are clamped within default bounds.
Definition at line 413 of file robot_state.cpp.
|
inline |
Set the acceleration of a variable. If an unknown variable name is specified, an exception is thrown.
Definition at line 447 of file robot_state.h.
|
inline |
Set the acceleration of a single variable. The variable is specified by its index (a value associated by the RobotModel to each variable)
Definition at line 454 of file robot_state.h.
|
inline |
Given an array with acceleration values for all variables, set those values as the accelerations in this state.
Definition at line 414 of file robot_state.h.
void moveit::core::RobotState::setVariableAccelerations | ( | const std::map< std::string, double > & | variable_map | ) |
Set the accelerations of a set of variables. If unknown variable names are specified, an exception is thrown.
Definition at line 521 of file robot_state.cpp.
void moveit::core::RobotState::setVariableAccelerations | ( | const std::map< std::string, double > & | variable_map, |
std::vector< std::string > & | missing_variables | ||
) |
Set the accelerations of a set of variables. If unknown variable names are specified, an exception is thrown. Additionally, missing_variables is filled with the names of the variables that are not set.
Definition at line 528 of file robot_state.cpp.
|
inline |
Given an array with acceleration values for all variables, set those values as the accelerations in this state.
Definition at line 425 of file robot_state.h.
void moveit::core::RobotState::setVariableAccelerations | ( | const std::vector< std::string > & | variable_names, |
const std::vector< double > & | variable_acceleration | ||
) |
Set the accelerations of a set of variables. If unknown variable names are specified, an exception is thrown.
Definition at line 535 of file robot_state.cpp.
|
inline |
Given an array with effort values for all variables, set those values as the effort in this state.
Definition at line 511 of file robot_state.h.
void moveit::core::RobotState::setVariableEffort | ( | const std::map< std::string, double > & | variable_map | ) |
Set the effort of a set of variables. If unknown variable names are specified, an exception is thrown.
Definition at line 544 of file robot_state.cpp.
void moveit::core::RobotState::setVariableEffort | ( | const std::map< std::string, double > & | variable_map, |
std::vector< std::string > & | missing_variables | ||
) |
Set the effort of a set of variables. If unknown variable names are specified, an exception is thrown. Additionally, missing_variables is filled with the names of the variables that are not set.
Definition at line 551 of file robot_state.cpp.
|
inline |
Set the effort of a variable. If an unknown variable name is specified, an exception is thrown.
Definition at line 538 of file robot_state.h.
|
inline |
Given an array with effort values for all variables, set those values as the effort in this state.
Definition at line 520 of file robot_state.h.
void moveit::core::RobotState::setVariableEffort | ( | const std::vector< std::string > & | variable_names, |
const std::vector< double > & | variable_acceleration | ||
) |
Set the effort of a set of variables. If unknown variable names are specified, an exception is thrown.
Definition at line 558 of file robot_state.cpp.
|
inline |
Set the effort of a single variable. The variable is specified by its index (a value associated by the RobotModel to each variable)
Definition at line 545 of file robot_state.h.
|
inline |
Set the position of a single variable. An exception is thrown if the variable name is not known.
Definition at line 254 of file robot_state.h.
|
inline |
Set the position of a single variable. The variable is specified by its index (a value associated by the RobotModel to each variable)
Definition at line 261 of file robot_state.h.
void moveit::core::RobotState::setVariablePositions | ( | const double * | position | ) |
It is assumed positions is an array containing the new positions for all variables in this state. Those values are copied into the state.
Definition at line 443 of file robot_state.cpp.
void moveit::core::RobotState::setVariablePositions | ( | const std::map< std::string, double > & | variable_map | ) |
Set the positions of a set of variables. If unknown variable names are specified, an exception is thrown.
Definition at line 455 of file robot_state.cpp.
void moveit::core::RobotState::setVariablePositions | ( | const std::map< std::string, double > & | variable_map, |
std::vector< std::string > & | missing_variables | ||
) |
Set the positions of a set of variables. If unknown variable names are specified, an exception is thrown. Additionally, missing_variables is filled with the names of the variables that are not set.
Definition at line 478 of file robot_state.cpp.
|
inline |
It is assumed positions is an array containing the new positions for all variables in this state. Those values are copied into the state.
Definition at line 233 of file robot_state.h.
void moveit::core::RobotState::setVariablePositions | ( | const std::vector< std::string > & | variable_names, |
const std::vector< double > & | variable_position | ||
) |
Set the positions of a set of variables. If unknown variable names are specified, an exception is thrown. Additionally, missing_variables is filled with the names of the variables that are not set.
Definition at line 485 of file robot_state.cpp.
|
inline |
Definition at line 1268 of file robot_state.h.
|
inline |
Given an array with velocity values for all variables, set those values as the velocities in this state.
Definition at line 319 of file robot_state.h.
void moveit::core::RobotState::setVariableVelocities | ( | const std::map< std::string, double > & | variable_map | ) |
Set the velocities of a set of variables. If unknown variable names are specified, an exception is thrown.
Definition at line 498 of file robot_state.cpp.
void moveit::core::RobotState::setVariableVelocities | ( | const std::map< std::string, double > & | variable_map, |
std::vector< std::string > & | missing_variables | ||
) |
Set the velocities of a set of variables. If unknown variable names are specified, an exception is thrown. Additionally, missing_variables is filled with the names of the variables that are not set.
Definition at line 505 of file robot_state.cpp.
|
inline |
Given an array with velocity values for all variables, set those values as the velocities in this state.
Definition at line 327 of file robot_state.h.
void moveit::core::RobotState::setVariableVelocities | ( | const std::vector< std::string > & | variable_names, |
const std::vector< double > & | variable_velocity | ||
) |
Set the velocities of a set of variables. If unknown variable names are specified, an exception is thrown.
Definition at line 512 of file robot_state.cpp.
|
inline |
Set the velocity of a variable. If an unknown variable name is specified, an exception is thrown.
Definition at line 348 of file robot_state.h.
|
inline |
Set the velocity of a single variable. The variable is specified by its index (a value associated by the RobotModel to each variable)
Definition at line 355 of file robot_state.h.
void moveit::core::RobotState::update | ( | bool | force = false | ) |
Update all transforms.
Definition at line 729 of file robot_state.cpp.
void moveit::core::RobotState::updateCollisionBodyTransforms | ( | ) |
Update the transforms for the collision bodies. This call is needed before calling collision checking. If updating link transforms or joint transorms is needed, the corresponding updates are also triggered.
Definition at line 742 of file robot_state.cpp.
void moveit::core::RobotState::updateLinkTransforms | ( | ) |
Update the reference frame transforms for links. This call is needed before using the transforms of links for coordinate transforms.
Definition at line 770 of file robot_state.cpp.
|
private |
Definition at line 784 of file robot_state.cpp.
|
inlineprivate |
Definition at line 1891 of file robot_state.h.
|
inlineprivate |
Update a set of joints that are certain to be mimicking other joints.
Definition at line 1903 of file robot_state.h.
|
inlineprivate |
Update all mimic joints within group.
Definition at line 1917 of file robot_state.h.
void moveit::core::RobotState::updateStateWithLinkAt | ( | const LinkModel * | link, |
const Eigen::Isometry3d & | transform, | ||
bool | backward = false |
||
) |
Update the state after setting a particular link to the input global transform pose.
Definition at line 823 of file robot_state.cpp.
|
inline |
Update the state after setting a particular link to the input global transform pose.
This "warps" the given link to the given pose, neglecting the joint values of its parent joint. The link transforms of link and all its descendants are updated, but not marked as dirty, although they do not match the joint values anymore! Collision body transforms are not yet updated, but marked dirty only. Use update(false) or updateCollisionBodyTransforms() to update them as well.
Definition at line 1367 of file robot_state.h.
void moveit::core::RobotState::zeroAccelerations | ( | ) |
Set all accelerations to 0.0.
Definition at line 319 of file robot_state.cpp.
void moveit::core::RobotState::zeroEffort | ( | ) |
Set all effort values to 0.0.
Definition at line 325 of file robot_state.cpp.
void moveit::core::RobotState::zeroVelocities | ( | ) |
Set all velocities to 0.0.
Definition at line 313 of file robot_state.cpp.
|
private |
Definition at line 1948 of file robot_state.h.
|
private |
All attached bodies that are part of this state, indexed by their name.
Definition at line 1966 of file robot_state.h.
|
private |
This event is called when there is a change in the attached bodies for this state; The event specifies the body that changed and whether it was just attached or about to be detached.
Definition at line 1970 of file robot_state.h.
|
private |
Definition at line 1955 of file robot_state.h.
|
private |
Definition at line 1963 of file robot_state.h.
|
private |
Definition at line 1954 of file robot_state.h.
|
private |
Definition at line 1949 of file robot_state.h.
|
private |
Transforms from model frame to collision bodies.
Definition at line 1962 of file robot_state.h.
|
private |
Transforms from model frame to link frame for each link.
Definition at line 1961 of file robot_state.h.
|
private |
Definition at line 1951 of file robot_state.h.
|
private |
Definition at line 1952 of file robot_state.h.
|
private |
Definition at line 1950 of file robot_state.h.
|
private |
Definition at line 1944 of file robot_state.h.
|
private |
Definition at line 1946 of file robot_state.h.
|
private |
For certain operations a state needs a random number generator. However, it may be slightly expensive to allocate the random number generator if many state instances are generated. For this reason, the generator is allocated on a need basis, by the getRandomNumberGenerator() function. Never use the rng_ member directly, but call getRandomNumberGenerator() instead.
Definition at line 1977 of file robot_state.h.
|
private |
Definition at line 1943 of file robot_state.h.
|
private |
Local transforms of all joints.
Definition at line 1960 of file robot_state.h.
|
private |
Definition at line 1947 of file robot_state.h.