A representation of a state of a Robot.  
 More...
#include <state.h>
 | 
 | 
|   | State (const Robot &robot) | 
|   | Constructor.  More...
  | 
|   | 
|   | State (const RobotPtr &robot) | 
|   | Constructor.  More...
  | 
|   | 
|   | State (const State &)=delete | 
|   | 
|   | State (State &&)=delete | 
|   | 
 | 
| void  | setJoint (const RobotPtr &robot, const std::string &name, double value) | 
|   | Sets the value of a frame with one joint parameter.  More...
  | 
|   | 
| void  | setTranslateJoint (const RobotPtr &robot, const std::string &name, const Eigen::Vector2d &value) | 
|   | Sets the value of a frame with a translation joint.  More...
  | 
|   | 
| void  | setFloatJoint (const RobotPtr &robot, const std::string &name, const Eigen::Isometry2d &value) | 
|   | Sets the value of a frame with a floating joint.  More...
  | 
|   | 
| void  | setFloatJoint (const RobotPtr &robot, const std::string &name, const Eigen::Vector3d &value) | 
|   | Sets the value of a frame with a floating joint.  More...
  | 
|   | 
| void  | setRandom (const RobotPtr &robot) | 
|   | Sets a random value to the state.  More...
  | 
|   | 
| void  | copy (const StatePtr &other) | 
|   | Copies the configuration from another state.  More...
  | 
|   | 
 | 
| void  | fk (const RobotPtr &robot) | 
|   | Compute the forward kinematics for all frames in the robot.  More...
  | 
|   | 
| const Eigen::Isometry2d &  | getPose (const RobotPtr &robot, const std::string &frame) | 
|   | Get the pose of a frame of the robot. fk() must be called before calling this function.  More...
  | 
|   | 
| const Eigen::MatrixXd &  | getJacobian (const RobotPtr &robot, const std::string &frame) | 
|   | Get the jacobian of a frame of the robot.  More...
  | 
|   | 
| const tf::EigenVector< Eigen::Isometry2d > &  | getGeometryPoses (const RobotPtr &robot, const std::string &frame) | 
|   | Get the poses of geometry attached to a frame of the robot. fk() must be called before calling this function.  More...
  | 
|   | 
 | 
| std::string  | printFrames (const RobotPtr &robot) const | 
|   | Print out the current value of all frames on the robot.  More...
  | 
|   | 
A representation of a state of a Robot. 
Definition at line 28 of file state.h.
 
◆ State() [1/4]
      
        
          | State::State  | 
          ( | 
          const Robot &  | 
          robot | ) | 
           | 
        
      
 
Constructor. 
- Parameters
 - 
  
    | [in] | robot | Robot that this is a state for.  | 
  
   
Definition at line 13 of file state.cpp.
 
 
◆ State() [2/4]
Constructor. 
- Parameters
 - 
  
    | [in] | robot | Robot that this is a state for.  | 
  
   
Definition at line 26 of file state.cpp.
 
 
◆ State() [3/4]
  
  
      
        
          | se2ez::State::State  | 
          ( | 
          const State &  | 
           | ) | 
           | 
         
       
   | 
  
delete   | 
  
 
 
◆ State() [4/4]
  
  
      
        
          | se2ez::State::State  | 
          ( | 
          State &&  | 
           | ) | 
           | 
         
       
   | 
  
delete   | 
  
 
 
◆ copy()
      
        
          | void State::copy  | 
          ( | 
          const StatePtr &  | 
          other | ) | 
           | 
        
      
 
Copies the configuration from another state. 
- Parameters
 - 
  
  
 
Definition at line 74 of file state.cpp.
 
 
◆ fk()
      
        
          | void State::fk  | 
          ( | 
          const RobotPtr &  | 
          robot | ) | 
           | 
        
      
 
Compute the forward kinematics for all frames in the robot. 
- Parameters
 - 
  
    | [in] | robot | Robot this state is for.  | 
  
   
Definition at line 80 of file state.cpp.
 
 
◆ getGeometryPoses()
Get the poses of geometry attached to a frame of the robot. fk() must be called before calling this function. 
- Parameters
 - 
  
    | [in] | robot | Robot this state is for.  | 
    | [in] | frame | Frame to get pose for.  | 
  
   
- Returns
 - Poses of the frame's geometry. 
 
Definition at line 104 of file state.cpp.
 
 
◆ getJacobian()
      
        
          | const Eigen::MatrixXd & State::getJacobian  | 
          ( | 
          const RobotPtr &  | 
          robot,  | 
        
        
           | 
           | 
          const std::string &  | 
          frame  | 
        
        
           | 
          ) | 
           |  | 
        
      
 
Get the jacobian of a frame of the robot. 
- Parameters
 - 
  
    | [in] | robot | Robot this state is for.  | 
    | [in] | frame | Frame to get jacobian for.  | 
  
   
- Returns
 - Jacobian of the frame. 
 
Definition at line 99 of file state.cpp.
 
 
◆ getPose()
Get the pose of a frame of the robot. fk() must be called before calling this function. 
- Parameters
 - 
  
    | [in] | robot | Robot this state is for.  | 
    | [in] | frame | Frame to get pose for.  | 
  
   
- Returns
 - Pose of the frame. 
 
Definition at line 91 of file state.cpp.
 
 
◆ printFrames()
Print out the current value of all frames on the robot. 
- Parameters
 - 
  
    | [in] | robot | Robot this state is for.  | 
  
   
- Returns
 - Tree of all frames with their poses. 
 
Definition at line 113 of file state.cpp.
 
 
◆ setFloatJoint() [1/2]
      
        
          | void State::setFloatJoint  | 
          ( | 
          const RobotPtr &  | 
          robot,  | 
        
        
           | 
           | 
          const std::string &  | 
          name,  | 
        
        
           | 
           | 
          const Eigen::Isometry2d &  | 
          value  | 
        
        
           | 
          ) | 
           |  | 
        
      
 
Sets the value of a frame with a floating joint. 
- Parameters
 - 
  
    | [in] | robot | Robot this state is for.  | 
    | [in] | name | Name of frame to set value of.  | 
    | [in] | value | Value to set.  | 
  
   
Definition at line 51 of file state.cpp.
 
 
◆ setFloatJoint() [2/2]
      
        
          | void State::setFloatJoint  | 
          ( | 
          const RobotPtr &  | 
          robot,  | 
        
        
           | 
           | 
          const std::string &  | 
          name,  | 
        
        
           | 
           | 
          const Eigen::Vector3d &  | 
          value  | 
        
        
           | 
          ) | 
           |  | 
        
      
 
Sets the value of a frame with a floating joint. 
- Parameters
 - 
  
    | [in] | robot | Robot this state is for.  | 
    | [in] | name | Name of frame to set value of.  | 
    | [in] | value | Value to set.  | 
  
   
Definition at line 57 of file state.cpp.
 
 
◆ setJoint()
Sets the value of a frame with one joint parameter. 
- Parameters
 - 
  
    | [in] | robot | Robot this state is for.  | 
    | [in] | name | Name of frame to set value of.  | 
    | [in] | value | Value to set.  | 
  
   
Definition at line 39 of file state.cpp.
 
 
◆ setRandom()
      
        
          | void State::setRandom  | 
          ( | 
          const RobotPtr &  | 
          robot | ) | 
           | 
        
      
 
Sets a random value to the state. 
- Parameters
 - 
  
    | [in] | robot | Robot this state is for.  | 
  
   
Definition at line 63 of file state.cpp.
 
 
◆ setTranslateJoint()
      
        
          | void State::setTranslateJoint  | 
          ( | 
          const RobotPtr &  | 
          robot,  | 
        
        
           | 
           | 
          const std::string &  | 
          name,  | 
        
        
           | 
           | 
          const Eigen::Vector2d &  | 
          value  | 
        
        
           | 
          ) | 
           |  | 
        
      
 
Sets the value of a frame with a translation joint. 
- Parameters
 - 
  
    | [in] | robot | Robot this state is for.  | 
    | [in] | name | Name of frame to set value of.  | 
    | [in] | value | Value to set.  | 
  
   
Definition at line 45 of file state.cpp.
 
 
◆ data
      
        
          | Eigen::VectorXd se2ez::State::data | 
        
      
 
Configuration vector. 
Definition at line 140 of file state.h.
 
 
◆ dirty
      
        
          | bool se2ez::State::dirty {true} | 
        
      
 
 
◆ frames
      
        
          | FrameMapPtr se2ez::State::frames {nullptr} | 
        
      
 
 
The documentation for this class was generated from the following files:
- /home/zak/code/se2ez_work/include/se2ez/core/state.h
 
- /home/zak/code/se2ez_work/src/core/state.cpp