43 #include <sensor_msgs/msg/joint_state.hpp>
44 #include <visualization_msgs/msg/marker_array.hpp>
45 #include <std_msgs/msg/color_rgba.hpp>
46 #include <geometry_msgs/msg/twist.hpp>
49 #include <rclcpp/duration.hpp>
68 typedef std::function<bool(RobotState* robot_state,
const JointModelGroup* joint_group,
69 const double* joint_group_variable_values)>
94 RobotState(
const RobotModelConstPtr& robot_model);
112 return robot_model_->getVariableCount();
118 return robot_model_->getVariableNames();
124 return robot_model_->getLinkModel(link);
130 return robot_model_->getJointModel(joint);
136 return robot_model_->getJointModelGroup(
group);
169 assert(robot_model_->getVariableCount() <= position.size());
180 std::vector<std::string>& missing_variables);
185 const std::vector<double>& variable_position);
197 position_[index] = value;
198 const JointModel* jm = robot_model_->getJointOfVariable(index);
201 markDirtyJointTransforms(jm);
202 updateMimicJoint(jm);
209 return position_[robot_model_->getVariableIndex(variable)];
217 return position_[index];
231 return has_velocity_;
255 has_velocity_ =
true;
257 memcpy(velocity_, velocity, robot_model_->getVariableCount() *
sizeof(
double));
263 assert(robot_model_->getVariableCount() <= velocity.size());
274 std::vector<std::string>& missing_variables);
279 const std::vector<double>& variable_velocity);
292 velocity_[index] = value;
298 return velocity_[robot_model_->getVariableIndex(variable)];
306 return velocity_[index];
324 return has_acceleration_;
333 return acceleration_;
340 return acceleration_;
350 has_acceleration_ =
true;
354 memcpy(acceleration_, acceleration, robot_model_->getVariableCount() *
sizeof(
double));
361 assert(robot_model_->getVariableCount() <= acceleration.size());
373 std::vector<std::string>& missing_variables);
378 const std::vector<double>& variable_acceleration);
391 acceleration_[index] = value;
397 return acceleration_[robot_model_->getVariableIndex(variable)];
405 return acceleration_[index];
448 has_acceleration_ =
false;
450 memcpy(effort_, effort, robot_model_->getVariableCount() *
sizeof(
double));
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);
482 effort_[index] = value;
488 return effort_[robot_model_->getVariableIndex(variable)];
496 return effort_[index];
533 markDirtyJointTransforms(joint);
534 updateMimicJoint(joint);
545 markDirtyJointTransforms(joint);
546 updateMimicJoint(joint);
551 has_velocity_ =
true;
607 const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
616 const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
628 assert(gstate.size() ==
group->getVariableCount());
640 const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
662 const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
680 const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
693 const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
706 const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
716 gstate.resize(
group->getVariableCount());
730 const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
750 const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
759 const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
779 const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
793 const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
806 const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
816 gstate.resize(
group->getVariableCount());
830 const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
850 const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
859 const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
879 const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
893 const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
906 const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
916 gstate.resize(
group->getVariableCount());
930 const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
1000 const std::vector<double>& consistency_limits,
double timeout = 0.0,
1015 const std::vector<std::string>& tips,
double timeout = 0.0,
1031 const std::vector<std::string>& tips,
const std::vector<std::vector<double>>& consistency_limits,
1045 const std::vector<std::string>& tips,
1046 const std::vector<std::vector<double>>& consistency_limits,
double timeout = 0.0,
1103 [[deprecated]]
double
1106 double jump_threshold_factor,
1119 [[deprecated]]
double
1121 const Eigen::Isometry3d& target,
bool global_reference_frame,
double max_step,
1122 double jump_threshold_factor,
1135 [[deprecated]]
double
1137 const EigenSTL::vector_Isometry3d&
waypoints,
bool global_reference_frame,
double max_step,
1138 double jump_threshold_factor,
1152 Eigen::MatrixXd& jacobian,
bool use_quaternion_representation =
false)
const;
1164 Eigen::MatrixXd& jacobian,
bool use_quaternion_representation =
false)
1168 use_quaternion_representation);
1221 if (!msg.position.empty())
1223 if (!msg.velocity.empty())
1267 random_numbers::RandomNumberGenerator& rng);
1277 const std::vector<double>& distances);
1287 const std::vector<double>& distances, random_numbers::RandomNumberGenerator& rng);
1304 void update(
bool force =
false);
1365 assert(checkLinkTransforms());
1397 assert(checkCollisionTransforms());
1409 unsigned char&
dirty = dirty_joint_transforms_[idx];
1415 return variable_joint_transforms_[idx];
1425 assert(checkJointTransforms(joint));
1436 return dirty_link_transforms_;
1441 return dirty_link_transforms_ || dirty_collision_body_transforms_;
1469 return joint->
distance(position_ + idx, other.position_ + idx);
1505 joint->
interpolate(position_ + idx, to.position_ + idx, t, state.position_ + idx);
1506 state.markDirtyJointTransforms(joint);
1507 state.updateMimicJoint(joint);
1522 markDirtyJointTransforms(joint);
1523 updateMimicJoint(joint);
1534 updateMimicJoint(joint);
1567 std::pair<double, const JointModel*>
1594 void attachBody(std::unique_ptr<AttachedBody> attached_body);
1634 void attachBody(
const std::string&
id,
const Eigen::Isometry3d& pose,
1635 const std::vector<shapes::ShapeConstPtr>&
shapes,
const EigenSTL::vector_Isometry3d& shape_poses,
1636 const std::set<std::string>& touch_links,
const std::string& link_name,
1637 const trajectory_msgs::msg::JointTrajectory& detach_posture = trajectory_msgs::msg::JointTrajectory(),
1657 void attachBody(
const std::string&
id,
const Eigen::Isometry3d& pose,
1658 const std::vector<shapes::ShapeConstPtr>&
shapes,
const EigenSTL::vector_Isometry3d& shape_poses,
1659 const std::vector<std::string>& touch_links,
const std::string& link_name,
1660 const trajectory_msgs::msg::JointTrajectory& detach_posture = trajectory_msgs::msg::JointTrajectory(),
1663 std::set<std::string> touch_links_set(touch_links.begin(), touch_links.end());
1664 attachBody(
id, pose,
shapes, shape_poses, touch_links_set, link_name, detach_posture, subframe_poses);
1668 void getAttachedBodies(std::vector<const AttachedBody*>& attached_bodies)
const;
1700 void computeAABB(std::vector<double>& aabb)
const;
1714 rng_ =
new random_numbers::RandomNumberGenerator();
1739 bool& frame_found)
const;
1751 void getRobotMarkers(visualization_msgs::msg::MarkerArray& arr,
const std::vector<std::string>& link_names,
1752 const std_msgs::msg::ColorRGBA& color,
const std::string& ns,
const rclcpp::Duration& dur,
1753 bool include_attached =
false)
const;
1762 void getRobotMarkers(visualization_msgs::msg::MarkerArray& arr,
const std::vector<std::string>& link_names,
1763 const std_msgs::msg::ColorRGBA& color,
const std::string& ns,
const rclcpp::Duration& dur,
1764 bool include_attached =
false)
1774 void getRobotMarkers(visualization_msgs::msg::MarkerArray& arr,
const std::vector<std::string>& link_names,
1775 bool include_attached =
false)
const;
1781 void getRobotMarkers(visualization_msgs::msg::MarkerArray& arr,
const std::vector<std::string>& link_names,
1782 bool include_attached =
false)
1797 void printTransform(
const Eigen::Isometry3d& transform, std::ostream& out = std::cout)
const;
1809 bool setToIKSolverFrame(Eigen::Isometry3d& pose,
const kinematics::KinematicsBaseConstPtr& solver);
1821 void initTransforms();
1824 void markDirtyJointTransforms(
const JointModel* joint)
1827 dirty_link_transforms_ =
1828 dirty_link_transforms_ ==
nullptr ? joint : robot_model_->getCommonRoot(dirty_link_transforms_, joint);
1831 void markDirtyJointTransforms(
const JointModelGroup*
group)
1833 for (
const JointModel* jm :
group->getActiveJointModels())
1834 dirty_joint_transforms_[jm->getJointIndex()] = 1;
1835 dirty_link_transforms_ = dirty_link_transforms_ ==
nullptr ?
1836 group->getCommonRoot() :
1837 robot_model_->getCommonRoot(dirty_link_transforms_,
group->getCommonRoot());
1840 void markVelocity();
1841 void markAcceleration();
1844 void updateMimicJoint(
const JointModel* joint)
1846 double v = position_[joint->getFirstVariableIndex()];
1847 for (
const JointModel* jm : joint->getMimicRequests())
1849 position_[jm->getFirstVariableIndex()] = jm->getMimicFactor() * v + jm->getMimicOffset();
1850 markDirtyJointTransforms(jm);
1856 [[deprecated]]
void updateMimicJoint(
const std::vector<const JointModel*>& mim)
1858 for (
const JointModel* jm : mim)
1860 const int fvi = jm->getFirstVariableIndex();
1861 position_[fvi] = jm->getMimicFactor() * position_[jm->getMimic()->getFirstVariableIndex()] + jm->getMimicOffset();
1865 dirty_joint_transforms_[jm->getJointIndex()] = 1;
1870 void updateMimicJoints(
const JointModelGroup*
group)
1872 for (
const JointModel* jm :
group->getMimicJointModels())
1874 const int fvi = jm->getFirstVariableIndex();
1875 position_[fvi] = jm->getMimicFactor() * position_[jm->getMimic()->getFirstVariableIndex()] + jm->getMimicOffset();
1876 markDirtyJointTransforms(jm);
1878 markDirtyJointTransforms(
group);
1881 void updateLinkTransformsInternal(
const JointModel* start);
1883 void getMissingKeys(
const std::map<std::string, double>& variable_map,
1884 std::vector<std::string>& missing_variables)
const;
1885 void getStateTreeJointString(std::ostream& ss,
const JointModel* jm,
const std::string& pfx0,
bool last)
const;
1888 bool checkJointTransforms(
const JointModel* joint)
const;
1891 bool checkLinkTransforms()
const;
1894 bool checkCollisionTransforms()
const;
1896 RobotModelConstPtr robot_model_;
1901 double* acceleration_;
1904 bool has_acceleration_;
1907 const JointModel* dirty_link_transforms_;
1908 const JointModel* dirty_collision_body_transforms_;
1913 Eigen::Isometry3d* variable_joint_transforms_;
1914 Eigen::Isometry3d* global_link_transforms_;
1915 Eigen::Isometry3d* global_collision_body_transforms_;
1916 unsigned char* dirty_joint_transforms_;
1919 std::map<std::string, std::unique_ptr<AttachedBody>> attached_body_map_;
1930 random_numbers::RandomNumberGenerator* rng_;
1934 std::ostream&
operator<<(std::ostream& out,
const RobotState& s);
std::function< double(const geometry_msgs::msg::Pose &, const moveit::core::RobotState &, moveit::core::JointModelGroup const *, const std::vector< double > &)> IKCostFn
Signature for a cost function used to evaluate IK solutions.
This may be thrown if unrecoverable errors occur.
Object defining bodies that can be attached to robot links.
unsigned int getVariableCount() const
Get the number of variables that describe this joint group. This includes variables necessary for mim...
unsigned int getActiveVariableCount() const
Get the number of variables that describe the active joints in this joint group. This excludes variab...
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
bool satisfiesVelocityBounds(const double *values, double margin=0.0) const
Check if the set of velocities for the variables of this joint are within bounds.
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 ...
size_t getJointIndex() const
Get the index of this joint within the robot model.
size_t getFirstVariableIndex() const
Get the index of this joint's first variable within the full robot state.
virtual bool harmonizePosition(double *values, const Bounds &other_bounds) 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....
std::size_t getVariableCount() const
Get the number of variables that describe this joint.
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)
bool enforceVelocityBounds(double *values) const
Force the specified velocities to be within bounds. Return true if changes were made.
virtual void computeTransform(const double *joint_values, Eigen::Isometry3d &transf) const =0
Given the joint values for a joint, compute the corresponding transform. The computed transform is gu...
bool enforcePositionBounds(double *values) const
Force the specified values to be inside bounds and normalized. Quaternions are normalized,...
bool satisfiesPositionBounds(const double *values, double margin=0.0) const
Check if the set of values for the variables of this joint are within bounds.
A link from the robot. Contains the constant transform applied to the link and its geometry.
int getFirstCollisionBodyTransformIndex() const
size_t getLinkIndex() const
The index of this joint when traversing the kinematic tree in depth first fashion.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
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 gr...
const double * getJointEffort(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....
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 zeroVelocities()
Set all velocities to 0.0.
const Eigen::Isometry3d & getCollisionBodyTransform(const std::string &link_name, std::size_t index) const
RobotState & operator=(const RobotState &other)
Copy operator.
const double * getJointPositions(const JointModel *joint) const
double getVariableVelocity(int index) const
Get the velocity of a particular variable. The variable is specified by its index....
void setVariableAcceleration(int index, double value)
Set the acceleration of a single variable. The variable is specified by its index (a value associated...
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 loca...
void setJointEfforts(const JointModel *joint, const double *effort)
void interpolate(const RobotState &to, double t, RobotState &state, const JointModel *joint) const
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::msg::JointTrajectory &detach_posture=trajectory_msgs::msg::JointTrajectory(), const moveit::core::FixedTransformsMap &subframe_poses=moveit::core::FixedTransformsMap())
Add an attached body to a link.
void enforceBounds(const JointModel *joint)
double getVariableEffort(const std::string &variable) const
Get the effort of a particular variable. An exception is thrown if the variable is not known.
bool satisfiesVelocityBounds(const JointModel *joint, double margin=0.0) const
void setAttachedBodyUpdateCallback(const AttachedBodyCallback &callback)
void setVariableAccelerations(const std::vector< double > &acceleration)
Given an array with acceleration values for all variables, set those values as the accelerations in t...
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 (includin...
void setJointVelocities(const JointModel *joint, const double *velocity)
double getVariableAcceleration(const std::string &variable) const
Get the acceleration of a particular variable. An exception is thrown if the variable is not known.
double getVariableAcceleration(int index) const
Get the acceleration of a particular variable. The variable is specified by its index....
void printTransforms(std::ostream &out=std::cout) const
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.
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 printTransform(const Eigen::Isometry3d &transform, std::ostream &out=std::cout) const
const double * getVariableEffort() const
Get const raw access to the effort of the variables that make up this state. The values are in the sa...
const double * getJointEffort(const std::string &joint_name) const
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 (includin...
const LinkModel * getLinkModel(const std::string &link) const
Get the model of a particular link.
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 loca...
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 ...
void attachBody(std::unique_ptr< AttachedBody > attached_body)
Add an attached body to this state.
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...
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 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 loca...
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.
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.
const double * getJointPositions(const std::string &joint_name) const
double getVariablePosition(int index) const
Get the position of a particular variable. The variable is specified by its index....
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 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...
void setVariablePosition(int index, double value)
Set the position of a single variable. The variable is specified by its index (a value associated by ...
bool hasVelocities() const
By default, if velocities are never set or initialized, the state remembers that there are no velocit...
void getRobotMarkers(visualization_msgs::msg::MarkerArray &arr, const std::vector< std::string > &link_names, const std_msgs::msg::ColorRGBA &color, const std::string &ns, const rclcpp::Duration &dur, bool include_attached=false)
Get a MarkerArray that fully describes the robot markers for a given robot. Update the state first.
void setVariableEffort(int index, double value)
Set the effort of a single variable. The variable is specified by its index (a value associated by th...
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.
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 loca...
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.
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 getAttachedBodies(std::vector< const AttachedBody * > &attached_bodies) const
Get all bodies attached to the model corresponding to this state.
const JointModel * getJointModel(const std::string &joint) const
Get the model of a particular joint.
const Eigen::Isometry3d & getJointTransform(const std::string &joint_name)
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...
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 chai...
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...
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 ...
const double * getJointVelocities(const JointModel *joint) const
void getRobotMarkers(visualization_msgs::msg::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.
bool hasAccelerations() const
By default, if accelerations are never set or initialized, the state remembers that there are no acce...
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 computeAABB(std::vector< double > &aabb) const
Compute an axis-aligned bounding box that contains the current state. The format for aabb is (minx,...
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...
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...
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 RobotModelConstPtr & getRobotModel() const
Get the robot model this state is constructed for.
void harmonizePositions()
Call harmonizePosition() for all joints / all joints in group / given joint.
void setVariableVelocities(const double *velocity)
Given an array with velocity values for all variables, set those values as the velocities in this sta...
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 v...
bool dirtyCollisionBodyTransforms() const
const Eigen::Isometry3d & getJointTransform(const JointModel *joint)
void zeroAccelerations()
Set all accelerations to 0.0.
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.
const double * getVariablePositions() const
Get a raw pointer to the positions of the variables stored in this state.
const Eigen::Isometry3d & getGlobalLinkTransform(const std::string &link_name) const
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.
double * getVariablePositions()
Get a raw pointer to the positions of the variables stored in this state. Use carefully....
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.
const JointModelGroup * getJointModelGroup(const std::string &group) const
Get the model of a particular joint group.
void setVariableVelocity(int index, double value)
Set the velocity of a single variable. The variable is specified by its index (a value associated by ...
const double * getJointVelocities(const std::string &joint_name) const
void dropDynamics()
Reduce RobotState to kinematic information (remove velocity, acceleration and effort,...
bool dirtyJointTransform(const JointModel *joint) 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 ...
bool dirty() const
Returns true if anything in this state is dirty.
bool hasEffort() const
By default, if effort is never set or initialized, the state remembers that there is no effort set....
void updateLinkTransforms()
Update the reference frame transforms for links. This call is needed before using the transforms of l...
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 gr...
double * getVariableVelocities()
Get raw access to the velocities of the variables that make up this state. The values are in the same...
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 loca...
double * getVariableEffort()
Get raw access to the effort of the variables that make up this state. The values are in the same ord...
void interpolate(const RobotState &to, double t, RobotState &state) const
double distance(const RobotState &other) const
Return the sum of joint distances to "other" state. An L1 norm. Only considers active joints.
const Eigen::Isometry3d & getJointTransform(const std::string &joint_name) const
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 (includin...
bool satisfiesPositionBounds(const JointModel *joint, double margin=0.0) const
std::string getStateTreeString() const
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 ...
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 setVariablePositions(const std::vector< double > &position)
It is assumed positions is an array containing the new positions for all variables in this state....
void setToRandomPositions()
Set all joints to random values. Values will be within default bounds.
bool satisfiesBounds(double margin=0.0) const
const double * getJointAccelerations(const JointModel *joint) const
void setVariableEffort(const double *effort)
Given an array with effort values for all variables, set those values as the effort in this state.
void setVariableVelocities(const std::vector< double > &velocity)
Given an array with velocity values for all variables, set those values as the velocities in this sta...
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 v...
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...
bool dirtyLinkTransforms() const
void setJointPositions(const JointModel *joint, const double *position)
void printStateInfo(std::ostream &out=std::cout) const
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 update(bool force=false)
Update all transforms.
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 va...
void dropAccelerations()
Remove accelerations from this state (this differs from setting them to zero)
const Eigen::Isometry3d & getGlobalLinkTransform(const LinkModel *link)
void getRobotMarkers(visualization_msgs::msg::MarkerArray &arr, const std::vector< std::string > &link_names, const std_msgs::msg::ColorRGBA &color, const std::string &ns, const rclcpp::Duration &dur, bool include_attached=false) const
Get a MarkerArray that fully describes the robot markers for a given robot.
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 v...
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 va...
const AttachedBody * getAttachedBody(const std::string &name) const
Get the attached body named name. Return nullptr if not found.
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...
const double * getVariableAccelerations() const
Get const raw access to the accelerations of the variables that make up this state....
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 setToDefaultValues()
Set all joints to their default positions. The default position is 0, or if that is not within bounds...
const Eigen::Isometry3d & getCollisionBodyTransform(const LinkModel *link, std::size_t index) const
void printStatePositions(std::ostream &out=std::cout) const
std::size_t getVariableCount() const
Get the number of variables that make up this state.
void printDirtyInfo(std::ostream &out=std::cout) const
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 loca...
void setVariableAccelerations(const double *acceleration)
Given an array with acceleration values for all variables, set those values as the accelerations in t...
double * getVariableAccelerations()
Get raw access to the accelerations of the variables that make up this state. The values are in the s...
void setJointPositions(const std::string &joint_name, const std::vector< double > &position)
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 ...
RobotState(const RobotModelConstPtr &robot_model)
A state can be constructed from a specified robot model. No values are initialized....
double computeCartesianPath(const JointModelGroup *group, std::vector< RobotStatePtr > &traj, const LinkModel *link, const Eigen::Vector3d &direction, bool global_reference_frame, double distance, double max_step, double jump_threshold_factor, const GroupStateValidityCallbackFn &validCallback=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions())
Compute the sequence of joint values that correspond to a straight Cartesian path for a particular gr...
void dropEffort()
Remove effort values from this state (this differs from setting them to zero)
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.
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),...
const double * getJointAccelerations(const std::string &joint_name) const
bool setToDefaultValues(const std::string &group_name, const std::string &state_name)
const Eigen::Isometry3d & getGlobalLinkTransform(const LinkModel *link) const
double getVariableEffort(int index) const
Get the effort of a particular variable. The variable is specified by its index. No checks are perfor...
void computeAABB(std::vector< double > &aabb)
Compute an axis-aligned bounding box that contains the current state. The format for aabb is (minx,...
void setVariableValues(const sensor_msgs::msg::JointState &msg)
void enforcePositionBounds(const JointModel *joint)
bool hasAttachedBody(const std::string &id) const
Check if an attached body named id exists in this state.
double distance(const RobotState &other, const JointModel *joint) const
Return the sum of joint distances to "other" state. An L1 norm. Only considers active joints.
void setJointPositions(const std::string &joint_name, const Eigen::Isometry3d &transform)
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 ...
void enforceVelocityBounds(const JointModel *joint)
const Eigen::Isometry3d & getCollisionBodyTransform(const LinkModel *link, std::size_t index)
random_numbers::RandomNumberGenerator & getRandomNumberGenerator()
Return the instance of a random number generator.
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 va...
void setJointPositions(const JointModel *joint, const std::vector< double > &position)
void setJointPositions(const JointModel *joint, const Eigen::Isometry3d &transform)
void invertVelocity()
Invert velocity if present.
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...
void harmonizePosition(const JointModel *joint)
void clearAttachedBodies()
Clear all attached bodies. This calls delete on the AttachedBody instances, if needed.
void dropVelocities()
Remove velocities from this state (this differs from setting them to zero)
void zeroEffort()
Set all effort values to 0.0.
const moveit::core::LinkModel * getRigidlyConnectedParentLinkModel(const std::string &frame) const
Get the latest link upwards the kinematic tree which is only connected via fixed joints.
bool satisfiesBounds(const JointModel *joint, double margin=0.0) const
void updateCollisionBodyTransforms()
Update the transforms for the collision bodies. This call is needed before calling collision checking...
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(), const kinematics::KinematicsBase::IKCostFn &cost_function=kinematics::KinematicsBase::IKCostFn())
Warning: This function inefficiently copies all transforms around. If the group consists of a set of ...
bool setFromIK(const JointModelGroup *group, const geometry_msgs::msg::Pose &pose, double timeout=0.0, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions(), const kinematics::KinematicsBase::IKCostFn &cost_function=kinematics::KinematicsBase::IKCostFn())
If the group this state corresponds to is a chain and a solver is available, then the joint values ca...
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 ...
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 setJointPositions(const std::string &joint_name, const double *position)
const Eigen::Isometry3d & getJointTransform(const JointModel *joint) const
const double * getVariableVelocities() const
Get const access to the velocities of the variables that make up this state. The values are in the sa...
Vec3fX< details::Vec3Data< double > > Vector3d
std::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_...
MOVEIT_CLASS_FORWARD(JointModelGroup)
std::ostream & operator<<(std::ostream &out, const VariableBounds &b)
Operator overload for printing variable bounds to a stream.
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...
std::function< void(AttachedBody *body, bool attached)> AttachedBodyCallback
Main namespace for MoveIt.
A set of options for the kinematics solver.