Go to the documentation of this file.
   43 #include <sensor_msgs/JointState.h> 
   44 #include <visualization_msgs/MarkerArray.h> 
   45 #include <std_msgs/ColorRGBA.h> 
   46 #include <geometry_msgs/Twist.h> 
   49 #include <boost/assert.hpp> 
   68 typedef boost::function<bool(RobotState* 
robot_state, 
const JointModelGroup* joint_group,
 
   69                              const double* joint_group_variable_values)>
 
  122   const LinkModel* 
getLinkModel(
const std::string& link)
 const 
  128   const JointModel* 
getJointModel(
const std::string& joint)
 const 
  169     assert(
robot_model_->getVariableCount() <= position.size());  
 
  180                             std::vector<std::string>& missing_variables);
 
  185                             const std::vector<double>& variable_position);
 
  263     assert(
robot_model_->getVariableCount() <= velocity.size());  
 
  274                              std::vector<std::string>& missing_variables);
 
  279                              const std::vector<double>& variable_velocity);
 
  361     assert(
robot_model_->getVariableCount() <= acceleration.size());  
 
  373                                 std::vector<std::string>& missing_variables);
 
  378                                 const std::vector<double>& variable_acceleration);
 
  456     assert(
robot_model_->getVariableCount() <= effort.size());  
 
  465   void setVariableEffort(
const std::map<std::string, double>& variable_map, std::vector<std::string>& missing_variables);
 
  469                          const std::vector<double>& variable_acceleration);
 
  532     memcpy(
position_ + joint->getFirstVariableIndex(), position, joint->getVariableCount() * 
sizeof(
double));
 
  537   void setJointPositions(
const std::string& joint_name, 
const Eigen::Isometry3d& transform)
 
  574     return velocity_ + joint->getFirstVariableIndex();
 
  662     const JointModelGroup* jmg = 
robot_model_->getJointModelGroup(joint_group_name);
 
  665       assert(gstate.size() == jmg->getActiveVariableCount());
 
  730     const JointModelGroup* jmg = 
robot_model_->getJointModelGroup(joint_group_name);
 
  750     const JointModelGroup* jmg = 
robot_model_->getJointModelGroup(joint_group_name);
 
  806     const JointModelGroup* jmg = 
robot_model_->getJointModelGroup(joint_group_name);
 
  906     const JointModelGroup* jmg = 
robot_model_->getJointModelGroup(joint_group_name);
 
  955   [[deprecated(
"The attempts argument is not supported anymore.")]] 
bool 
  960     return setFromIK(group, pose, timeout, constraint, options);
 
  973   [[deprecated(
"The attempts argument is not supported anymore.")]] 
bool 
  975             unsigned int , 
double timeout = 0.0,
 
  979     return setFromIK(group, pose, tip, timeout, constraint, options);
 
  991   [[deprecated(
"The attempts argument is not supported anymore.")]] 
bool 
  996     return setFromIK(group, pose, timeout, constraint, options);
 
 1008   [[deprecated(
"The attempts argument is not supported anymore.")]] 
bool 
 1010             unsigned int , 
double timeout = 0.0,
 
 1014     return setFromIK(group, pose, tip, timeout, constraint, options);
 
 1025   bool setFromIK(
const JointModelGroup* group, 
const Eigen::Isometry3d& pose, 
const std::string& tip,
 
 1026                  const std::vector<double>& consistency_limits, 
double timeout = 0.0,
 
 1029   [[deprecated(
"The attempts argument is not supported anymore.")]] 
bool 
 1030   setFromIK(
const JointModelGroup* group, 
const Eigen::Isometry3d& pose, 
const std::string& tip,
 
 1031             const std::vector<double>& consistency_limits, 
unsigned int , 
double timeout = 0.0,
 
 1035     return setFromIK(group, pose, tip, consistency_limits, timeout, constraint, options);
 
 1048                  const std::vector<std::string>& tips, 
double timeout = 0.0,
 
 1051   [[deprecated(
"The attempts argument is not supported anymore.")]] 
bool 
 1053             const std::vector<std::string>& tips, 
unsigned int , 
double timeout = 0.0,
 
 1057     return setFromIK(group, poses, tips, timeout, constraint, options);
 
 1071                  const std::vector<std::string>& tips, 
const std::vector<std::vector<double>>& consistency_limits,
 
 1074   [[deprecated(
"The attempts argument is not supported anymore.")]] 
bool 
 1076             const std::vector<std::string>& tips, 
const std::vector<std::vector<double>>& consistency_limits,
 
 1077             unsigned int , 
double timeout = 0.0,
 
 1081     return setFromIK(group, poses, tips, consistency_limits, timeout, constraint, options);
 
 1093                           const std::vector<std::string>& tips,
 
 1094                           const std::vector<std::vector<double>>& consistency_limits, 
double timeout = 0.0,
 
 1097   [[deprecated(
"The attempts argument is not supported anymore.")]] 
bool 
 1099                      const std::vector<std::string>& tips, 
const std::vector<std::vector<double>>& consistency_limits,
 
 1100                      unsigned int , 
double timeout = 0.0,
 
 1104     return setFromIKSubgroups(group, poses, tips, consistency_limits, timeout, constraint, options);
 
 1135                    Eigen::MatrixXd& jacobian, 
bool use_quaternion_representation = 
false) 
const;
 
 1147                    Eigen::MatrixXd& jacobian, 
bool use_quaternion_representation = 
false)
 
 1150     return static_cast<const RobotState*
>(
this)->
getJacobian(group, link, reference_point_position, jacobian,
 
 1151                                                              use_quaternion_representation);
 
 1160   Eigen::MatrixXd 
getJacobian(
const JointModelGroup* group,
 
 1169   Eigen::MatrixXd 
getJacobian(
const JointModelGroup* group,
 
 1193                              const Eigen::Vector3d& reference_point_position, Eigen::MatrixXd& jacobian,
 
 1194                              Eigen::MatrixXd& jacobian_derivative) 
const;
 
 1203                                                                         int column_index, 
int joint_index);
 
 1208                                const LinkModel* tip) 
const;
 
 1233     if (!msg.position.empty())
 
 1235     if (!msg.velocity.empty())
 
 1247   bool setToDefaultValues(
const std::string& group_name, 
const std::string& state_name)
 
 1293                                   const std::vector<double>& distances);
 
 1320   void update(
bool force = 
false);
 
 1330   void updateStateWithLinkAt(
const std::string& link_name, 
const Eigen::Isometry3d& transform, 
bool backward = 
false)
 
 1418     const int idx = joint->getJointIndex();
 
 1516     state.markDirtyJointTransforms(joint);
 
 1517     state.updateMimicJoint(joint);
 
 1542     if (joint->harmonizePosition(
position_ + joint->getFirstVariableIndex()))
 
 1553   bool satisfiesBounds(
const JointModelGroup* joint_group, 
double margin = 0.0) 
const;
 
 1554   bool satisfiesBounds(
const JointModel* joint, 
double margin = 0.0)
 const 
 1577   std::pair<double, const JointModel*>
 
 1604   void attachBody(std::unique_ptr<AttachedBody> attached_body);
 
 1644   void attachBody(
const std::string& 
id, 
const Eigen::Isometry3d& pose,
 
 1646                   const std::set<std::string>& touch_links, 
const std::string& link_name,
 
 1647                   const trajectory_msgs::JointTrajectory& detach_posture = trajectory_msgs::JointTrajectory(),
 
 1667   void attachBody(
const std::string& 
id, 
const Eigen::Isometry3d& pose,
 
 1669                   const std::vector<std::string>& touch_links, 
const std::string& link_name,
 
 1670                   const trajectory_msgs::JointTrajectory& detach_posture = trajectory_msgs::JointTrajectory(),
 
 1673     std::set<std::string> touch_links_set(touch_links.begin(), touch_links.end());
 
 1674     attachBody(
id, pose, 
shapes, shape_poses, touch_links_set, link_name, detach_posture, subframe_poses);
 
 1678   void getAttachedBodies(std::vector<const AttachedBody*>& attached_bodies) 
const;
 
 1710   void computeAABB(std::vector<double>& aabb) 
const;
 
 1733   const Eigen::Isometry3d& 
getFrameTransform(
const std::string& frame_id, 
bool* frame_found = 
nullptr);
 
 1740   const Eigen::Isometry3d& 
getFrameTransform(
const std::string& frame_id, 
bool* frame_found = 
nullptr) 
const;
 
 1749                                         bool& frame_found) 
const;
 
 1761   void getRobotMarkers(visualization_msgs::MarkerArray& arr, 
const std::vector<std::string>& link_names,
 
 1762                        const std_msgs::ColorRGBA& color, 
const std::string& ns, 
const ros::Duration& dur,
 
 1763                        bool include_attached = 
false) 
const;
 
 1772   void getRobotMarkers(visualization_msgs::MarkerArray& arr, 
const std::vector<std::string>& link_names,
 
 1773                        const std_msgs::ColorRGBA& color, 
const std::string& ns, 
const ros::Duration& dur,
 
 1774                        bool include_attached = 
false)
 
 1784   void getRobotMarkers(visualization_msgs::MarkerArray& arr, 
const std::vector<std::string>& link_names,
 
 1785                        bool include_attached = 
false) 
const;
 
 1791   void getRobotMarkers(visualization_msgs::MarkerArray& arr, 
const std::vector<std::string>& link_names,
 
 1792                        bool include_attached = 
false)
 
 1807   void printTransform(
const Eigen::Isometry3d& transform, std::ostream& out = std::cout) 
const;
 
 1819   bool setToIKSolverFrame(Eigen::Isometry3d& pose, 
const kinematics::KinematicsBaseConstPtr& solver);
 
 1856     double v = 
position_[joint->getFirstVariableIndex()];
 
 1866   [[deprecated]] 
void updateMimicJoint(
const std::vector<const JointModel*>& mim)
 
 1868     for (
const JointModel* jm : mim)
 
 1882     for (
const JointModel* jm : group->getMimicJointModels())
 
 1893   void getMissingKeys(
const std::map<std::string, double>& variable_map,
 
 1894                       std::vector<std::string>& missing_variables) 
const;
 
 1895   void getStateTreeJointString(std::ostream& ss, 
const JointModel* jm, 
const std::string& pfx0, 
bool last) 
const;
 
  
void dropAccelerations()
Remove accelerations from this state (this differs from setting them to zero)
A link from the robot. Contains the constant transform applied to the link and its geometry.
Core components of MoveIt.
bool checkJointTransforms(const JointModel *joint) const
This function is only called in debug mode.
boost::function< bool(RobotState *robot_state, const JointModelGroup *joint_group, const double *joint_group_variable_values)> GroupStateValidityCallbackFn
Signature for functions that can verify that if the group joint_group in robot_state is set to joint_...
const std::vector< const JointModel * > & getActiveJointModels() const
Get the active joints in this group (that have controllable DOF). This does not include mimic joints.
bool enforcePositionBounds(double *values) const
Force the specified values to be inside bounds and normalized. Quaternions are normalized,...
void setJointPositions(const std::string &joint_name, const double *position)
RobotState & operator=(const RobotState &other)
Copy operator.
double distance(const RobotState &other) const
Return the sum of joint distances to "other" state. Only considers active joints.
bool dirtyJointTransform(const JointModel *joint) const
void setVariablePositions(const double *position)
It is assumed positions is an array containing the new positions for all variables in this state....
std::vector< Eigen::Isometry3d, Eigen::aligned_allocator< Eigen::Isometry3d > > vector_Isometry3d
std::ostream & operator<<(std::ostream &out, const VariableBounds &b)
Operator overload for printing variable bounds to a stream.
double getVariableVelocity(const std::string &variable) const
Get the velocity of a particular variable. An exception is thrown if the variable is not known.
void harmonizePosition(const JointModel *joint)
std::size_t getVariableCount() const
Get the number of variables that describe this joint.
double getMimicOffset() const
If mimicking a joint, this is the offset added to that joint's value.
const JointModel * getJointModel(const std::string &joint) const
Get the model of a particular joint.
std::size_t getVariableCount() const
Get the number of variables that make up this state.
bool enforceVelocityBounds(double *values) const
Force the specified velocities to be within bounds. Return true if changes were made.
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 v...
unsigned int getActiveVariableCount() const
Get the number of variables that describe the active joints in this joint group. This excludes variab...
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 solv...
void getStateTreeJointString(std::ostream &ss, const JointModel *jm, const std::string &pfx0, bool last) const
virtual void interpolate(const double *from, const double *to, const double t, double *state) const =0
Computes the state that lies at time t in [0, 1] on the segment that connects from state to to state....
void setVariableVelocities(const double *velocity)
Given an array with velocity values for all variables, set those values as the velocities in this sta...
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_i...
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.
void zeroAccelerations()
Set all accelerations to 0.0.
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.
const LinkModel * getLinkModel(const std::string &link) const
Get the model of a particular link.
double * getVariableAccelerations()
Get raw access to the accelerations of the variables that make up this state. The values are in the s...
bool hasAccelerations() const
By default, if accelerations are never set or initialized, the state remembers that there are no acce...
void copyFrom(const RobotState &other)
void dropDynamics()
Reduce RobotState to kinematic information (remove velocity, acceleration and effort,...
bool hasVelocities() const
By default, if velocities are never set or initialized, the state remembers that there are no velocit...
void updateLinkTransformsInternal(const JointModel *start)
const Eigen::Isometry3d & getJointTransform(const std::string &joint_name)
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 gr...
double getMimicFactor() const
If mimicking a joint, this is the multiplicative factor for that joint's value.
const AttachedBody * getAttachedBody(const std::string &name) const
Get the attached body named name. Return NULL if not found.
double * getVariableEffort()
Get raw access to the effort of the variables that make up this state. The values are in the same ord...
Representation of a robot's state. This includes position, velocity, acceleration and effort.
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 loca...
std::map< std::string, std::unique_ptr< AttachedBody > > attached_body_map_
All attached bodies that are part of this state, indexed by their name.
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 ro...
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 ca...
void setToRandomPositions()
Set all joints to random values. Values will be within default bounds.
bool getJacobianDerivative(const JointModelGroup *group, const LinkModel *link, const Eigen::Vector3d &reference_point_position, Eigen::MatrixXd &jacobian, Eigen::MatrixXd &jacobian_derivative) const
Compute the time derivative of the Jacobian with reference to a particular point on a given link,...
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 ...
template Halfspace< double > transform(const Halfspace< double > &a, const Transform3< double > &tf)
const double * getJointAccelerations(const std::string &joint_name) const
void setAttachedBodyUpdateCallback(const AttachedBodyCallback &callback)
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.
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.
void printStatePositions(std::ostream &out=std::cout) 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 t...
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.
bool checkCollisionTransforms() const
This function is only called in debug mode.
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.
void clearAttachedBodies()
Clear all attached bodies. This calls delete on the AttachedBody instances, if needed.
void getMissingKeys(const std::map< std::string, double > &variable_map, std::vector< std::string > &missing_variables) const
std::string getStateTreeString() const
Object defining bodies that can be attached to robot links.
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 ...
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.
void harmonizePositions()
Call harmonizePosition() for all joints / all joints in group / given joint.
random_numbers::RandomNumberGenerator & getRandomNumberGenerator()
Return the instance of a random number generator.
void printDirtyInfo(std::ostream &out=std::cout) const
bool satisfiesPositionBounds(const JointModel *joint, double margin=0.0) const
RobotState(const RobotModelConstPtr &robot_model)
A state can be constructed from a specified robot model. No values are initialized....
void markDirtyJointTransforms(const JointModel *joint)
void printTransform(const Eigen::Isometry3d &transform, std::ostream &out=std::cout) const
bool dirtyLinkTransforms() const
void update(bool force=false)
Update all transforms.
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.
void dropVelocities()
Remove velocities from this state (this differs from setting them to zero)
int getFirstVariableIndex() const
Get the index of this joint's first variable within the full robot state.
const JointModel * dirty_link_transforms_
void printTransforms(std::ostream &out=std::cout) const
const RobotModelConstPtr & getRobotModel() const
Get the robot model this state is constructed for.
const std::vector< const JointModel * > & getMimicRequests() const
The joint models whose values would be modified if the value of this joint changed.
void attachBody(std::unique_ptr< AttachedBody > attached_body)
Add an attached body to this state.
const JointModel * getCommonRoot() const
Get the common root of all joint roots; not necessarily part of this group.
double getVariablePosition(const std::string &variable) const
Get the position of a particular variable. An exception is thrown if the variable is not known.
void setToDefaultValues()
Set all joints to their default positions. The default position is 0, or if that is not within bounds...
void setVariableEffort(const double *effort)
Given an array with effort values for all variables, set those values as the effort in this state.
const double * getJointEffort(const std::string &joint_name) const
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 ...
Eigen::Isometry3d * global_link_transforms_
Transforms from model frame to link frame for each link.
void updateMimicJoints(const JointModelGroup *group)
Update all mimic joints within group.
void computeAABB(std::vector< double > &aabb) const
Compute an axis-aligned bounding box that contains the current state. The format for aabb is (minx,...
void setJointEfforts(const JointModel *joint, const double *effort)
random_numbers::RandomNumberGenerator * rng_
For certain operations a state needs a random number generator. However, it may be slightly expensive...
void getAttachedBodies(std::vector< const AttachedBody * > &attached_bodies) const
Get all bodies attached to the model corresponding to this state.
boost::function< void(AttachedBody *body, bool attached)> AttachedBodyCallback
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.
std::map< std::string, Eigen::Isometry3d, std::less< std::string >, Eigen::aligned_allocator< std::pair< const std::string, Eigen::Isometry3d > > > FixedTransformsMap
Map frame names to the transformation matrix that can transform objects from the frame name to the pl...
int getJointIndex() const
Get the index of this joint within the robot model.
void enforcePositionBounds(const JointModel *joint)
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())
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.
Eigen::Isometry3d * global_collision_body_transforms_
Transforms from model frame to collision bodies.
Eigen::Isometry3d * variable_joint_transforms_
Local transforms of all joints.
void updateLinkTransforms()
Update the reference frame transforms for links. This call is needed before using the transforms of l...
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),...
double * getVariablePositions()
Get a raw pointer to the positions of the variables stored in this state. Use carefully....
bool dirty() const
Returns true if anything in this state is dirty.
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_i...
void updateCollisionBodyTransforms()
Update the transforms for the collision bodies. This call is needed before calling collision checking...
void zeroEffort()
Set all effort values to 0.0.
void zeroVelocities()
Set all velocities to 0.0.
static Eigen::Matrix< double, 6, 1 > getJacobianColumnPartialDerivative(const Eigen::MatrixXd &jacobian, int column_index, int joint_index)
Compute the partial derivative of a column of the Jacobian wrt a single joint.
double * getVariableVelocities()
Get raw access to the velocities of the variables that make up this state. The values are in the same...
bool checkLinkTransforms() const
This function is only called in debug mode.
Main namespace for MoveIt.
std::vector< double > values
const JointModel * getMimic() const
Get the joint this one is mimicking.
A set of options for the kinematics solver.
bool clearAttachedBody(const std::string &id)
Remove the attached body named id. Return false if the object was not found (and thus not removed)....
const double * getJointPositions(const std::string &joint_name) const
unsigned char * dirty_joint_transforms_
MOVEIT_CLASS_FORWARD(JointModelGroup)
void invertVelocity()
Invert velocity if present.
bool satisfiesBounds(double margin=0.0) 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 ro...
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 loca...
AttachedBodyCallback attached_body_update_callback_
This event is called when there is a change in the attached bodies for this state; The event specifie...
void interpolate(const RobotState &to, double t, RobotState &state) const
virtual double distance(const double *value1, const double *value2) const =0
Compute the distance between two joint states of the same model (represented by the variable values)
double getVariableAcceleration(const std::string &variable) const
Get the acceleration of a particular variable. An exception is thrown if the variable is not known.
void setJointVelocities(const JointModel *joint, const double *velocity)
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 (includin...
RobotModelConstPtr robot_model_
void setVariableAccelerations(const double *acceleration)
Given an array with acceleration values for all variables, set those values as the accelerations in t...
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.
void enforceVelocityBounds(const JointModel *joint)
unsigned int getVariableCount() const
Get the number of variables that describe this joint group. This includes variables necessary for mim...
bool hasEffort() const
By default, if effort is never set or initialized, the state remembers that there is no effort set....
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 va...
const JointModelGroup * getJointModelGroup(const std::string &group) const
Get the model of a particular joint group.
bool haveSameAttachedObjects(const RobotState &left, const RobotState &right, const std::string &logprefix="")
void setVariableValues(const sensor_msgs::JointState &msg)
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.
void printStateInfo(std::ostream &out=std::cout) const
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.
virtual void computeVariablePositions(const Eigen::Isometry3d &transform, double *joint_values) const =0
Given the transform generated by joint, compute the corresponding joint values. Make sure the passed ...
void dropEffort()
Remove effort values from this state (this differs from setting them to zero)
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
void updateMimicJoint(const JointModel *joint)
bool dirtyCollisionBodyTransforms() const
bool hasAttachedBody(const std::string &id) const
Check if an attached body named id exists in this state.
bool satisfiesVelocityBounds(const JointModel *joint, double margin=0.0) const
const double * getJointVelocities(const std::string &joint_name) const
Vec3fX< details::Vec3Data< double > > Vector3d
const JointModel * dirty_collision_body_transforms_
moveit_core
Author(s): Ioan Sucan 
, Sachin Chitta , Acorn Pooley 
autogenerated on Sat May 3 2025 02:25:32