Public Types | Public Member Functions | List of all members
tesseract_scene_graph::MutableStateSolver Class Referenceabstract

A mutable state solver allows you to reconfigure the solver's links and joints. More...

#include <mutable_state_solver.h>

Inheritance diagram for tesseract_scene_graph::MutableStateSolver:
Inheritance graph
[legend]

Public Types

using ConstPtr = std::shared_ptr< const MutableStateSolver >
 
using ConstUPtr = std::unique_ptr< const MutableStateSolver >
 
using Ptr = std::shared_ptr< MutableStateSolver >
 
using UPtr = std::unique_ptr< MutableStateSolver >
 
- Public Types inherited from tesseract_scene_graph::StateSolver
using ConstPtr = std::shared_ptr< const StateSolver >
 
using ConstUPtr = std::unique_ptr< const StateSolver >
 
using Ptr = std::shared_ptr< StateSolver >
 
using UPtr = std::unique_ptr< StateSolver >
 

Public Member Functions

virtual bool addLink (const Link &link, const Joint &joint)=0
 Adds a link/joint to the solver. More...
 
virtual bool changeJointAccelerationLimits (const std::string &name, double limit)=0
 Changes the acceleration limits associated with a joint. More...
 
virtual bool changeJointJerkLimits (const std::string &name, double limit)=0
 Changes the jerk limits associated with a joint. More...
 
virtual bool changeJointOrigin (const std::string &name, const Eigen::Isometry3d &new_origin)=0
 Changes the "origin" transform of the joint and recomputes the associated edge. More...
 
virtual bool changeJointPositionLimits (const std::string &name, double lower, double upper)=0
 Changes the position limits associated with a joint. More...
 
virtual bool changeJointVelocityLimits (const std::string &name, double limit)=0
 Changes the velocity limits associated with a joint. More...
 
virtual int getRevision () const =0
 Get the state solver revision number. More...
 
virtual bool insertSceneGraph (const SceneGraph &scene_graph, const Joint &joint, const std::string &prefix="")=0
 Merge a scene into the current solver. More...
 
virtual bool moveJoint (const std::string &name, const std::string &parent_link)=0
 Move joint to new parent link. More...
 
virtual bool moveLink (const Joint &joint)=0
 Move a link. More...
 
 MutableStateSolver ()=default
 
 MutableStateSolver (const MutableStateSolver &)=default
 
 MutableStateSolver (MutableStateSolver &&)=default
 
MutableStateSolveroperator= (const MutableStateSolver &)=default
 
MutableStateSolveroperator= (MutableStateSolver &&)=default
 
virtual bool removeJoint (const std::string &name)=0
 Removes a joint from the graph. More...
 
virtual bool removeLink (const std::string &name)=0
 Removes a link from the graph. More...
 
virtual bool replaceJoint (const Joint &joint)=0
 Replace and existing joint with the provided one. More...
 
virtual void setRevision (int revision)=0
 Set the state solver revision number. More...
 
 ~MutableStateSolver () override=default
 
- Public Member Functions inherited from tesseract_scene_graph::StateSolver
virtual StateSolver::UPtr clone () const =0
 This should clone the object so it may be used in a multi threaded application where each thread would clone the solver. More...
 
virtual std::vector< std::string > getActiveJointNames () const =0
 Get the vector of joint names which align with the limits. More...
 
virtual std::vector< std::string > getActiveLinkNames () const =0
 Get the vector of active link names. More...
 
virtual std::string getBaseLinkName () const =0
 Get the base link name. More...
 
virtual std::vector< std::string > getFloatingJointNames () const =0
 Get the vector of floating joint names. More...
 
virtual Eigen::MatrixXd getJacobian (const Eigen::Ref< const Eigen::VectorXd > &joint_values, const std::string &link_name, const tesseract_common::TransformMap &floating_joint_values={}) const =0
 Get the jacobian of the solver given the joint values. More...
 
virtual Eigen::MatrixXd getJacobian (const std::unordered_map< std::string, double > &joint_values, const std::string &link_name, const tesseract_common::TransformMap &floating_joint_values={}) const =0
 Get the jacobian of the scene for a given set or subset of joint values. More...
 
virtual Eigen::MatrixXd getJacobian (const std::vector< std::string > &joint_names, const Eigen::Ref< const Eigen::VectorXd > &joint_values, const std::string &link_name, const tesseract_common::TransformMap &floating_joint_values={}) const =0
 
virtual std::vector< std::string > getJointNames () const =0
 Get the vector of joint names. More...
 
virtual tesseract_common::KinematicLimits getLimits () const =0
 Getter for kinematic limits. More...
 
virtual std::vector< std::string > getLinkNames () const =0
 Get the vector of link names. More...
 
virtual Eigen::Isometry3d getLinkTransform (const std::string &link_name) const =0
 Get the transform corresponding to the link. More...
 
virtual tesseract_common::VectorIsometry3d getLinkTransforms () const =0
 Get all of the links transforms. More...
 
virtual SceneState getRandomState () const =0
 Get the random state of the environment. More...
 
virtual Eigen::Isometry3d getRelativeLinkTransform (const std::string &from_link_name, const std::string &to_link_name) const =0
 Get transform between two links using the current state. More...
 
virtual SceneState getState () const =0
 Get the current state of the scene. More...
 
virtual SceneState getState (const Eigen::Ref< const Eigen::VectorXd > &joint_values, const tesseract_common::TransformMap &floating_joint_values={}) const =0
 Get the state of the solver given the joint values. More...
 
virtual SceneState getState (const std::unordered_map< std::string, double > &joint_values, const tesseract_common::TransformMap &floating_joint_values={}) const =0
 Get the state of the scene for a given set or subset of joint values. More...
 
virtual SceneState getState (const std::vector< std::string > &joint_names, const Eigen::Ref< const Eigen::VectorXd > &joint_values, const tesseract_common::TransformMap &floating_joint_values={}) const =0
 
virtual SceneState getState (const tesseract_common::TransformMap &floating_joint_values) const =0
 Get the state given floating joint values. More...
 
virtual std::vector< std::string > getStaticLinkNames () const =0
 Get a vector of static link names in the environment. More...
 
virtual bool hasLinkName (const std::string &link_name) const =0
 Check if link name exists. More...
 
virtual bool isActiveLinkName (const std::string &link_name) const =0
 Check if link is an active link. More...
 
StateSolveroperator= (const StateSolver &)=default
 
StateSolveroperator= (StateSolver &&)=default
 
virtual void setState (const Eigen::Ref< const Eigen::VectorXd > &joint_values, const tesseract_common::TransformMap &floating_joint_values={})=0
 Set the current state of the solver. More...
 
virtual void setState (const std::unordered_map< std::string, double > &joint_values, const tesseract_common::TransformMap &floating_joint_values={})=0
 Set the current state of the solver. More...
 
virtual void setState (const std::vector< std::string > &joint_names, const Eigen::Ref< const Eigen::VectorXd > &joint_values, const tesseract_common::TransformMap &floating_joint_values={})=0
 
virtual void setState (const tesseract_common::TransformMap &floating_joint_values)=0
 Set the current state of the floating joint values. More...
 
 StateSolver ()=default
 
 StateSolver (const StateSolver &)=default
 
 StateSolver (StateSolver &&)=default
 
virtual ~StateSolver ()=default
 

Detailed Description

A mutable state solver allows you to reconfigure the solver's links and joints.

Definition at line 36 of file mutable_state_solver.h.

Member Typedef Documentation

◆ ConstPtr

Definition at line 40 of file mutable_state_solver.h.

◆ ConstUPtr

Definition at line 42 of file mutable_state_solver.h.

◆ Ptr

Definition at line 39 of file mutable_state_solver.h.

◆ UPtr

Definition at line 41 of file mutable_state_solver.h.

Constructor & Destructor Documentation

◆ MutableStateSolver() [1/3]

tesseract_scene_graph::MutableStateSolver::MutableStateSolver ( )
default

◆ ~MutableStateSolver()

tesseract_scene_graph::MutableStateSolver::~MutableStateSolver ( )
overridedefault

◆ MutableStateSolver() [2/3]

tesseract_scene_graph::MutableStateSolver::MutableStateSolver ( const MutableStateSolver )
default

◆ MutableStateSolver() [3/3]

tesseract_scene_graph::MutableStateSolver::MutableStateSolver ( MutableStateSolver &&  )
default

Member Function Documentation

◆ addLink()

virtual bool tesseract_scene_graph::MutableStateSolver::addLink ( const Link link,
const Joint joint 
)
pure virtual

Adds a link/joint to the solver.

Parameters
linkThe link to be added to the graph
jointThe associated joint to be added to the graph
Returns
Return False if a link with the same name allready exists, otherwise true

Implemented in tesseract_scene_graph::OFKTStateSolver.

◆ changeJointAccelerationLimits()

virtual bool tesseract_scene_graph::MutableStateSolver::changeJointAccelerationLimits ( const std::string &  name,
double  limit 
)
pure virtual

Changes the acceleration limits associated with a joint.

Parameters
joint_nameName of the joint to be updated
limitsNew acceleration limits to be set as the joint limits
Returns

Implemented in tesseract_scene_graph::OFKTStateSolver.

◆ changeJointJerkLimits()

virtual bool tesseract_scene_graph::MutableStateSolver::changeJointJerkLimits ( const std::string &  name,
double  limit 
)
pure virtual

Changes the jerk limits associated with a joint.

Parameters
joint_nameName of the joint to be updated
limitsNew jerk limits to be set as the joint limits
Returns

Implemented in tesseract_scene_graph::OFKTStateSolver.

◆ changeJointOrigin()

virtual bool tesseract_scene_graph::MutableStateSolver::changeJointOrigin ( const std::string &  name,
const Eigen::Isometry3d &  new_origin 
)
pure virtual

Changes the "origin" transform of the joint and recomputes the associated edge.

Parameters
nameName of the joint to be changed
new_originThe new transform associated with the joint
Returns
True if successful.

Implemented in tesseract_scene_graph::OFKTStateSolver.

◆ changeJointPositionLimits()

virtual bool tesseract_scene_graph::MutableStateSolver::changeJointPositionLimits ( const std::string &  name,
double  lower,
double  upper 
)
pure virtual

Changes the position limits associated with a joint.

Parameters
joint_nameName of the joint to be updated
limitsNew position limits to be set as the joint limits @returnTrue if successful.

Implemented in tesseract_scene_graph::OFKTStateSolver.

◆ changeJointVelocityLimits()

virtual bool tesseract_scene_graph::MutableStateSolver::changeJointVelocityLimits ( const std::string &  name,
double  limit 
)
pure virtual

Changes the velocity limits associated with a joint.

Parameters
joint_nameName of the joint to be updated
limitsNew velocity limits to be set as the joint limits
Returns

Implemented in tesseract_scene_graph::OFKTStateSolver.

◆ getRevision()

virtual int tesseract_scene_graph::MutableStateSolver::getRevision ( ) const
pure virtual

Get the state solver revision number.

Returns
revision number

Implemented in tesseract_scene_graph::OFKTStateSolver.

◆ insertSceneGraph()

virtual bool tesseract_scene_graph::MutableStateSolver::insertSceneGraph ( const SceneGraph scene_graph,
const Joint joint,
const std::string &  prefix = "" 
)
pure virtual

Merge a scene into the current solver.

Parameters
scene_graphConst ref to the graph to be merged
jointThe joint that connects current scene with the inserted scene
prefixstring Will be prepended to every link and joint of the merged scene
Returns
Return False if any link or joint name collides with current solver, otherwise True The prefix argument is meant to allow adding multiple copies of the same subgraph with different names

Implemented in tesseract_scene_graph::OFKTStateSolver.

◆ moveJoint()

virtual bool tesseract_scene_graph::MutableStateSolver::moveJoint ( const std::string &  name,
const std::string &  parent_link 
)
pure virtual

Move joint to new parent link.

Parameters
nameName of the joint to move
parent_linkName of parent link to move to
Returns
Returns true if successful, otherwise false.

Implemented in tesseract_scene_graph::OFKTStateSolver.

◆ moveLink()

virtual bool tesseract_scene_graph::MutableStateSolver::moveLink ( const Joint joint)
pure virtual

Move a link.

Parameters
jointThe associated joint that defines the move
Returns
Return False if link does not exist or if joint name already exists, otherwise true

Implemented in tesseract_scene_graph::OFKTStateSolver.

◆ operator=() [1/2]

MutableStateSolver& tesseract_scene_graph::MutableStateSolver::operator= ( const MutableStateSolver )
default

◆ operator=() [2/2]

MutableStateSolver& tesseract_scene_graph::MutableStateSolver::operator= ( MutableStateSolver &&  )
default

◆ removeJoint()

virtual bool tesseract_scene_graph::MutableStateSolver::removeJoint ( const std::string &  name)
pure virtual

Removes a joint from the graph.

Parameters
nameName of the joint to be removed
Returns
Return False if a joint does not exists, otherwise true

Implemented in tesseract_scene_graph::OFKTStateSolver.

◆ removeLink()

virtual bool tesseract_scene_graph::MutableStateSolver::removeLink ( const std::string &  name)
pure virtual

Removes a link from the graph.

Note: this will remove all inbound and outbound edges

Parameters
nameName of the link to be removed
Returns
Return False if a link does not exists, otherwise true

Implemented in tesseract_scene_graph::OFKTStateSolver.

◆ replaceJoint()

virtual bool tesseract_scene_graph::MutableStateSolver::replaceJoint ( const Joint joint)
pure virtual

Replace and existing joint with the provided one.

Parameters
jointThe replacement joint
Returns
Return False if a joint does not exists, otherwise true

Implemented in tesseract_scene_graph::OFKTStateSolver.

◆ setRevision()

virtual void tesseract_scene_graph::MutableStateSolver::setRevision ( int  revision)
pure virtual

Set the state solver revision number.

Parameters
revisionThe revision number to assign

Implemented in tesseract_scene_graph::OFKTStateSolver.


The documentation for this class was generated from the following file:


tesseract_state_solver
Author(s): Levi Armstrong
autogenerated on Sun May 18 2025 03:02:10