se2ez
se2ez::Robot Class Reference

A representation of a robot (in this case, a kinematic tree in the plane). More...

#include <robot.h>

Classes

class  FrameData
 All associated data with a frame in a kinematic tree. More...
 
class  FrameDataConstPtr
 A const shared pointer wrapper for se2ez::Robot::FrameData. More...
 
class  FrameDataPtr
 A shared pointer wrapper for se2ez::Robot::FrameData. More...
 

Public Member Functions

Constructors
 Robot ()
 Constructor. Nothing interesting right now. More...
 
 Robot (const Robot &)=delete
 
 Robot (Robot &&)=delete
 
Getters and Setters
unsigned int getNumJoints () const
 Gets the number of controllable joints within the tree. More...
 
const std::vector< std::string > & getEEs () const
 Gets the names of end-effectors of the tree (leaf nodes). More...
 
const std::vector< std::string > & getFrameNames () const
 Get a vector of all the frame names within this robot. More...
 
FramePtr getFrame (const std::string &name)
 Get the frame with name name. More...
 
FramePtr getFrameParent (const std::string &name)
 Get the parent of frame with name name. Throws Error if name is root. More...
 
const FramePtrgetFrameConst (const std::string &name) const
 Get the frame with name name. More...
 
bool inTree (const std::string &name) const
 Checks if a frame name is in the tree. More...
 
const FrameDataPtrgetFrameDataConst (const std::string &frame_name) const
 Retrieves kinematic tree data associated with the frame frame_name. More...
 
const std::stringgetSignature ()
 Returns the signature of the robot. More...
 
void setNamedState (const std::string &name, const StatePtr &state)
 Sets a named state. More...
 
void setNamedStates (const std::map< std::string, StatePtr > &named)
 Sets a named state. More...
 
void getNamedState (const std::string &name, StatePtr state)
 Gets a named state. More...
 
std::vector< std::stringgetNamedStates () const
 Gets the names of all named states. More...
 
const std::map< std::string, StatePtr > & getNamedStatesMap ()
 Gets the names of all named states. More...
 
ACMPtr getACM ()
 Gets the robot's default ACM. More...
 
void setACM (const ACMPtr &acm)
 Sets the robot's default ACM. More...
 
const Eigen::VectorXd getUpperLimits () const
 Get the upper limits of the joints for this robot. More...
 
const Eigen::VectorXd getLowerLimits () const
 Get the lower limits of the joints for this robot. More...
 
const std::vector< bool > getContinuity () const
 Returns a vector of booleans. If an entry is true, that index is a continuous joint. More...
 
const std::vector< std::pair< std::string, FrameDataPtr > > & getJoints () const
 Get the ordered list of active joints in this robot with their associated frame information. More...
 
const KDL::Tree & getTree () const
 Get the underlying KDL tree for this robot. More...
 

Private Member Functions

Getters / Setters
FrameDataPtr getFrameData (const std::string &frame_name)
 Retrieves kinematic tree data associated with the frame frame_name. More...
 

Private Attributes

std::map< std::string, FrameDataPtrdata_
 Kinematic tree data for all frames. More...
 
std::vector< std::stringees_
 End-effectors (leaves) in the kinematic tree that are mobile. More...
 
std::vector< std::stringnames_
 Names of the the kinematic tree frames (ordered). More...
 
std::vector< std::pair< std::string, FrameDataPtr > > joints_
 Ordered vector of active joints. More...
 
Eigen::VectorXd upper_
 Upper limits of joints. More...
 
Eigen::VectorXd lower_
 Lower limits of joints. More...
 
unsigned int maxDepth_
 Maximum tree depth. More...
 
KDL::Tree tree_
 Underlying tree representation. More...
 
std::shared_ptr< KDL::TreeJntToJacSolver > jac_ {nullptr}
 Underlying tree representation. More...
 
bool tree_update_ {true}
 Does the tree need recompiling? More...
 
std::map< std::string, StatePtrnamed_
 Named states. More...
 
std::string signature_
 A string that represents the current kinematic chain. More...
 
ACMPtr acm_
 Default robot ACM. More...
 
FrameMapPtr static_ {nullptr}
 Transforms for all non-movable links. More...
 

Frame / Kinematic Tree Management

void attachFrame (const FramePtr &frame)
 Attach a frame to the root of the kinematic tree. Will detach frame if attached elsewhere already. More...
 
void attachFrame (const FramePtr &frame, const FramePtr &parent)
 Attach a frame to another frame in the kinematic tree. Will detach frame if attached elsewhere already. More...
 
void attachFrame (const FramePtr &frame, const std::string &parent_name)
 Attach a frame to another frame in the kinematic tree. Will detach frame if attached elsewhere already. More...
 
void detachFrame (const FramePtr &frame)
 Detach a frame from a kinematic tree. If frame has children all children will be detached as well. More...
 
void detachFrame (const std::string &frame_name)
 Detach a frame from a kinematic tree. If frame has children all children will be detached as well. More...
 
void addFixedRobot (const RobotPtr &frobot, const StatePtr &state, const std::string &scene_name)
 add a fixed Robot(frames with all joints fixed) on the current robot. The frame names are namespaced under the scene_name. More...
 
void addActiveRobot (const RobotPtr &arobot)
 adds an active Robot with all its frames and corresponding joints. More...
 
void compileTree ()
 Compiles the underlying kinematic tree representation after a call to attachFrame(). More...
 
void clear ()
 Completely clears internal structures, a brand new robot! More...
 
void removeChild (FrameDataPtr parent, const std::string &child)
 Removes child from the parent in the tree. More...
 
void updateFrame (const FramePtr &frame, const std::string &parent_name)
 Updates a frame's entry in the kinematic tree with a possibly new parent parent_name. More...
 
void compileTreeRecursive (const std::string &previous, FrameDataPtr &data, bool movable=false)
 Helper function to compileTree() that recursively build tree representation. More...
 
void staticFK ()
 Compute the transform for all non-movable frames. More...
 
void generateSignature ()
 Creates a unique signature (based on active joints). More...
 

Pose / Configuration Management

void fk (const Eigen::Ref< const Eigen::VectorXd > &q, FrameMapPtr frames) const
 Compute the forward kinematics of the robot at a state q. More...
 
const FrameMap::ValuegetPose (const std::string &frame_name, const Eigen::Ref< const Eigen::VectorXd > &q, FrameMapPtr frames) const
 Gets the pose of a frame frame_name at a configuration q. Also updates all dependent frames in frames. More...
 
const FrameMap::ValuegetJacobian (const std::string &frame_name, const Eigen::Ref< const Eigen::VectorXd > &q, FrameMapPtr frames) const
 Gets the jacobian for frame_name at configuration q. More...
 
Eigen::Ref< Eigen::VectorXd > getFrameValues (const std::string &frame_name, Eigen::Ref< Eigen::VectorXd > q) const
 Returns a reference to the underlying subvector of the configuration associated with a specific frame. More...
 
const Eigen::Ref< const Eigen::VectorXd > getFrameValuesConst (const std::string &frame_name, const Eigen::Ref< const Eigen::VectorXd > &q) const
 Returns a reference to the underlying subvector of the configuration associated with a specific frame. More...
 
double distance (const StatePtr &a, const StatePtr &b, bool weighted=true) const
 Compute the distance between two states. More...
 
void enforceLimits (StatePtr a) const
 Enforce joint limits on a robot and renormalize angles if necessary. More...
 
bool inLimits (const StatePtr &a) const
 Check if all configuration parameters are within limits. More...
 
void interpolate (const StatePtr &from, const StatePtr &to, double t, StatePtr state) const
 Interpolate between two states. More...
 
const FrameMap::ValuegetPose (const FrameDataPtr &data, const Eigen::Ref< const Eigen::VectorXd > &q, FrameMapPtr frames) const
 Gets the pose of a frame data at a configuration q. Also updates all dependent frames in frames. More...
 

Informative

using PrintHelper = std::function< std::string(const FrameDataPtr &)>
 Function used by Robot::printTree() to print additional information about frames. More...
 
std::string printTree (const PrintHelper &function={}) const
 Returns a string that graphically shows the kinematic structure of the tree. For example: More...
 
std::string printDebug () const
 Returns a string of complete robot information for debugging purposes. More...
 
void printTreeRecursive (std::stringstream &ss, const FrameDataPtr &frame, const PrintHelper &function, const std::string &prefix="") const
 Helper function to printTree() that recursively traverses the kinematic tree. More...
 

Detailed Description

A representation of a robot (in this case, a kinematic tree in the plane).

Definition at line 119 of file robot.h.

Member Typedef Documentation

◆ PrintHelper

Function used by Robot::printTree() to print additional information about frames.

Definition at line 459 of file robot.h.

Constructor & Destructor Documentation

◆ Robot() [1/3]

Robot::Robot ( )

Constructor. Nothing interesting right now.

Robot

Definition at line 106 of file robot.cpp.

◆ Robot() [2/3]

se2ez::Robot::Robot ( const Robot )
delete

◆ Robot() [3/3]

se2ez::Robot::Robot ( Robot &&  )
delete

Member Function Documentation

◆ addActiveRobot()

void Robot::addActiveRobot ( const RobotPtr arobot)

adds an active Robot with all its frames and corresponding joints.

Parameters
[in]arobotRobot to add as the active one.

Definition at line 188 of file robot.cpp.

◆ addFixedRobot()

void Robot::addFixedRobot ( const RobotPtr frobot,
const StatePtr state,
const std::string scene_name 
)

add a fixed Robot(frames with all joints fixed) on the current robot. The frame names are namespaced under the scene_name.

Parameters
[in]frobotRobot to add as a fixed scene.
[in]stateState of the attached Scene;
[in]scene_namestd::string name of the attached scene

Definition at line 173 of file robot.cpp.

◆ attachFrame() [1/3]

void Robot::attachFrame ( const FramePtr frame)

Attach a frame to the root of the kinematic tree. Will detach frame if attached elsewhere already.

Parameters
[in]frameFrame to attach.

Frame / Kinematic Tree Updating

Definition at line 124 of file robot.cpp.

◆ attachFrame() [2/3]

void Robot::attachFrame ( const FramePtr frame,
const FramePtr parent 
)

Attach a frame to another frame in the kinematic tree. Will detach frame if attached elsewhere already.

Parameters
[in]frameFrame to attach.
[in]parentParent to attach frame to (must be in tree already).

Definition at line 129 of file robot.cpp.

◆ attachFrame() [3/3]

void Robot::attachFrame ( const FramePtr frame,
const std::string parent_name 
)

Attach a frame to another frame in the kinematic tree. Will detach frame if attached elsewhere already.

Parameters
[in]frameFrame to attach.
[in]parent_nameName of parent to attach frame to.

Definition at line 133 of file robot.cpp.

◆ clear()

void Robot::clear ( )

Completely clears internal structures, a brand new robot!

Definition at line 111 of file robot.cpp.

◆ compileTree()

void Robot::compileTree ( )

Compiles the underlying kinematic tree representation after a call to attachFrame().

Definition at line 253 of file robot.cpp.

◆ compileTreeRecursive()

void Robot::compileTreeRecursive ( const std::string previous,
FrameDataPtr data,
bool  movable = false 
)
private

Helper function to compileTree() that recursively build tree representation.

Parameters
[in]previousPrevious frame in the kinematic tree.
[in]dataFrame to add to the tree.
[in]movableWas there a movable joint before this frame?

Definition at line 296 of file robot.cpp.

◆ detachFrame() [1/2]

void Robot::detachFrame ( const FramePtr frame)

Detach a frame from a kinematic tree. If frame has children all children will be detached as well.

Parameters
[in]frameFrame to detach

Definition at line 144 of file robot.cpp.

◆ detachFrame() [2/2]

void Robot::detachFrame ( const std::string frame_name)

Detach a frame from a kinematic tree. If frame has children all children will be detached as well.

Parameters
[in]frame_nameFrame name to detach.

Definition at line 149 of file robot.cpp.

◆ distance()

double Robot::distance ( const StatePtr a,
const StatePtr b,
bool  weighted = true 
) const

Compute the distance between two states.

Parameters
[in]aOne state.
[in]bOther state.
[in]weightedWeight distance by inverse of depth of frame in tree.
Returns
The distance between a and b.

Definition at line 596 of file robot.cpp.

◆ enforceLimits()

void Robot::enforceLimits ( StatePtr  a) const

Enforce joint limits on a robot and renormalize angles if necessary.

Parameters
[in,out]aState to enforce limits on.

Definition at line 615 of file robot.cpp.

◆ fk()

void Robot::fk ( const Eigen::Ref< const Eigen::VectorXd > &  q,
FrameMapPtr  frames 
) const

Compute the forward kinematics of the robot at a state q.

Parameters
[in]qConfiguration of the robot.
[out]framesForward kinematics.

Definition at line 534 of file robot.cpp.

◆ generateSignature()

void Robot::generateSignature ( )
private

Creates a unique signature (based on active joints).

Returns
the robot signature

Definition at line 347 of file robot.cpp.

◆ getACM()

ACMPtr Robot::getACM ( )

Gets the robot's default ACM.

Returns
The robot's ACM.

Definition at line 468 of file robot.cpp.

◆ getContinuity()

const std::vector< bool > Robot::getContinuity ( ) const

Returns a vector of booleans. If an entry is true, that index is a continuous joint.

Returns
Continuity of joints.

Definition at line 488 of file robot.cpp.

◆ getEEs()

const std::vector< std::string > & Robot::getEEs ( ) const

Gets the names of end-effectors of the tree (leaf nodes).

Returns
Vector of all end-effectors in the tree.

Definition at line 370 of file robot.cpp.

◆ getFrame()

FramePtr Robot::getFrame ( const std::string name)

Get the frame with name name.

Parameters
[in]nameName of the frame to get.
Returns
Frame information.

Definition at line 380 of file robot.cpp.

◆ getFrameConst()

const FramePtr & Robot::getFrameConst ( const std::string name) const

Get the frame with name name.

Parameters
[in]nameName of the frame to get.
Returns
Frame information.

Definition at line 393 of file robot.cpp.

◆ getFrameData()

Robot::FrameDataPtr Robot::getFrameData ( const std::string frame_name)
private

Retrieves kinematic tree data associated with the frame frame_name.

Parameters
[in]frame_nameName of frame to get data for.
Returns
The frame data of the frame. Throws exception if frame does not exist.

Definition at line 403 of file robot.cpp.

◆ getFrameDataConst()

const Robot::FrameDataPtr & Robot::getFrameDataConst ( const std::string frame_name) const

Retrieves kinematic tree data associated with the frame frame_name.

Parameters
[in]frame_nameName of frame to get data for.
Returns
The frame data of the frame.
Exceptions
Exceptionif frame does not exist.

Definition at line 412 of file robot.cpp.

◆ getFrameNames()

const std::vector< std::string > & Robot::getFrameNames ( ) const

Get a vector of all the frame names within this robot.

Returns
A vector of all frame names.

Definition at line 375 of file robot.cpp.

◆ getFrameParent()

FramePtr Robot::getFrameParent ( const std::string name)

Get the parent of frame with name name. Throws Error if name is root.

Parameters
[in]nameName of the frame to get.
Returns
Frame information.

Definition at line 385 of file robot.cpp.

◆ getFrameValues()

Eigen::Ref< Eigen::VectorXd > Robot::getFrameValues ( const std::string frame_name,
Eigen::Ref< Eigen::VectorXd >  q 
) const

Returns a reference to the underlying subvector of the configuration associated with a specific frame.

Parameters
[in]frame_nameName of frame to get component of configuration for.
[in]qConfiguration to extract component from.
Returns
Reference to subvector within configuration associated with a frame's joint values.

Pose / Configuration Management

Definition at line 522 of file robot.cpp.

◆ getFrameValuesConst()

const Eigen::Ref< const Eigen::VectorXd > Robot::getFrameValuesConst ( const std::string frame_name,
const Eigen::Ref< const Eigen::VectorXd > &  q 
) const

Returns a reference to the underlying subvector of the configuration associated with a specific frame.

Parameters
[in]frame_nameName of frame to get component of configuration for.
[in]qConfiguration to extract component from.
Returns
Reference to subvector within configuration associated with a frame's joint values.

Definition at line 529 of file robot.cpp.

◆ getJacobian()

const FrameMap::Value & Robot::getJacobian ( const std::string frame_name,
const Eigen::Ref< const Eigen::VectorXd > &  q,
FrameMapPtr  frames 
) const

Gets the jacobian for frame_name at configuration q.

Parameters
[in]frame_nameName of frame to get jacobian for.
[in]qConfiguration of robot to compute jacobian for.
[in]framesWorkspace for computing jacobian.

Definition at line 574 of file robot.cpp.

◆ getJoints()

const std::vector< std::pair< std::string, Robot::FrameDataPtr > > & Robot::getJoints ( ) const

Get the ordered list of active joints in this robot with their associated frame information.

Returns
The ordered list of active joints.

Definition at line 508 of file robot.cpp.

◆ getLowerLimits()

const Eigen::VectorXd Robot::getLowerLimits ( ) const

Get the lower limits of the joints for this robot.

Returns
The lower limits of the robot.

Definition at line 483 of file robot.cpp.

◆ getNamedState()

void Robot::getNamedState ( const std::string name,
StatePtr  state 
)

Gets a named state.

Parameters
[in]nameName of state to get.
[out]stateState to fill with named state.

Definition at line 439 of file robot.cpp.

◆ getNamedStates()

std::vector< std::string > Robot::getNamedStates ( ) const

Gets the names of all named states.

Returns
List of state names.

Definition at line 448 of file robot.cpp.

◆ getNamedStatesMap()

const std::map< std::string, StatePtr > & Robot::getNamedStatesMap ( )

Gets the names of all named states.

Returns
map of state names.

Definition at line 457 of file robot.cpp.

◆ getNumJoints()

unsigned int Robot::getNumJoints ( ) const

Gets the number of controllable joints within the tree.

Getters and Setters

Definition at line 365 of file robot.cpp.

◆ getPose() [1/2]

const FrameMap::Value & Robot::getPose ( const std::string frame_name,
const Eigen::Ref< const Eigen::VectorXd > &  q,
FrameMapPtr  frames 
) const

Gets the pose of a frame frame_name at a configuration q. Also updates all dependent frames in frames.

Parameters
[in]frame_nameName of frame to get pose for.
[in]qConfiguration of robot to compute pose for.
[in]framesWorkspace for computing frames. Respects dirty frame information.
Returns
Current pose of the frame.

Definition at line 542 of file robot.cpp.

◆ getPose() [2/2]

const FrameMap::Value & Robot::getPose ( const FrameDataPtr data,
const Eigen::Ref< const Eigen::VectorXd > &  q,
FrameMapPtr  frames 
) const
private

Gets the pose of a frame data at a configuration q. Also updates all dependent frames in frames.

Parameters
[in]dataFrame data to get pose for.
[in]qConfiguration of robot to compute pose for.
[in]framesWorkspace for computing frames. Respects dirty frame information.
Returns
Current pose of the frame.

Definition at line 549 of file robot.cpp.

◆ getSignature()

const std::string & Robot::getSignature ( )

Returns the signature of the robot.

Returns
the robot signature

Definition at line 421 of file robot.cpp.

◆ getTree()

const KDL::Tree & Robot::getTree ( ) const

Get the underlying KDL tree for this robot.

Returns
The KDL tree.

Definition at line 513 of file robot.cpp.

◆ getUpperLimits()

const Eigen::VectorXd Robot::getUpperLimits ( ) const

Get the upper limits of the joints for this robot.

Returns
The upper limits of the robot.

Definition at line 478 of file robot.cpp.

◆ inLimits()

bool Robot::inLimits ( const StatePtr a) const

Check if all configuration parameters are within limits.

Parameters
[in]aState to check.
Returns
True if within limits, false otherwise.

Definition at line 628 of file robot.cpp.

◆ interpolate()

void Robot::interpolate ( const StatePtr from,
const StatePtr to,
double  t,
StatePtr  state 
) const

Interpolate between two states.

Parameters
[in]fromState you are interpolating from.
[in]toState you are interpolating to.
[in]tInterpolation parameter in [0, 1]. 0 is from, 1 is to.
[out]stateInterpolated state.

Definition at line 642 of file robot.cpp.

◆ inTree()

bool Robot::inTree ( const std::string name) const

Checks if a frame name is in the tree.

Parameters
[in]nameFrame to check.
Returns
True if frame is in tree, false otherwise.

Definition at line 398 of file robot.cpp.

◆ printDebug()

std::string Robot::printDebug ( ) const

Returns a string of complete robot information for debugging purposes.

Returns
A string of tree information.

Informative

Definition at line 660 of file robot.cpp.

◆ printTree()

std::string Robot::printTree ( const PrintHelper function = {}) const

Returns a string that graphically shows the kinematic structure of the tree. For example:

* \_ root (output of function goes here)
*  \_ base
*   \_ link_1
*    \_ link_2
*    |\_ link_3
*    | \_ e2
*    \_ e1
* 
Parameters
[in]functionA function to be called for each frame, with output attached at end of tree.
Returns
A string that represents the tree.

Definition at line 687 of file robot.cpp.

◆ printTreeRecursive()

void Robot::printTreeRecursive ( std::stringstream ss,
const FrameDataPtr frame,
const PrintHelper function,
const std::string prefix = "" 
) const
private

Helper function to printTree() that recursively traverses the kinematic tree.

Parameters
[in]ssStream to output data to.
[in]frameFrame to output data about.
[in]functionUser provided function to call for each frame.
[in]prefixPrefix to attach to frame output.

Definition at line 694 of file robot.cpp.

◆ removeChild()

void Robot::removeChild ( FrameDataPtr  parent,
const std::string child 
)
private

Removes child from the parent in the tree.

Parameters
[in]parentParent to remove child from.
[in]childName of child to remove.
Exceptions
Exceptionif child is not a child of parent.

Definition at line 211 of file robot.cpp.

◆ setACM()

void Robot::setACM ( const ACMPtr acm)

Sets the robot's default ACM.

Parameters
[in]acmThe ACM to set.

Definition at line 473 of file robot.cpp.

◆ setNamedState()

void Robot::setNamedState ( const std::string name,
const StatePtr state 
)

Sets a named state.

Parameters
[in]nameName of state to set.
[in]stateState to set named state to.

Definition at line 426 of file robot.cpp.

◆ setNamedStates()

void Robot::setNamedStates ( const std::map< std::string, StatePtr > &  named)

Sets a named state.

Parameters
[in]namedMap of named states.

Definition at line 462 of file robot.cpp.

◆ staticFK()

void Robot::staticFK ( )
private

Compute the transform for all non-movable frames.

Definition at line 333 of file robot.cpp.

◆ updateFrame()

void Robot::updateFrame ( const FramePtr frame,
const std::string parent_name 
)
private

Updates a frame's entry in the kinematic tree with a possibly new parent parent_name.

Parameters
[in]frameFrame to update (will also add frame if new).
[in]parent_nameName of parent frame in kinematic tree.

Definition at line 224 of file robot.cpp.

Member Data Documentation

◆ acm_

ACMPtr se2ez::Robot::acm_
private

Default robot ACM.

Definition at line 575 of file robot.h.

◆ data_

std::map<std::string, FrameDataPtr> se2ez::Robot::data_
private

Kinematic tree data for all frames.

Definition at line 559 of file robot.h.

◆ ees_

std::vector<std::string> se2ez::Robot::ees_
private

End-effectors (leaves) in the kinematic tree that are mobile.

Definition at line 560 of file robot.h.

◆ jac_

std::shared_ptr<KDL::TreeJntToJacSolver> se2ez::Robot::jac_ {nullptr}
private

Underlying tree representation.

Definition at line 569 of file robot.h.

◆ joints_

std::vector<std::pair<std::string, FrameDataPtr> > se2ez::Robot::joints_
private

Ordered vector of active joints.

Definition at line 563 of file robot.h.

◆ lower_

Eigen::VectorXd se2ez::Robot::lower_
private

Lower limits of joints.

Definition at line 565 of file robot.h.

◆ maxDepth_

unsigned int se2ez::Robot::maxDepth_
private

Maximum tree depth.

Definition at line 566 of file robot.h.

◆ named_

std::map<std::string, StatePtr> se2ez::Robot::named_
private

Named states.

Definition at line 572 of file robot.h.

◆ names_

std::vector<std::string> se2ez::Robot::names_
private

Names of the the kinematic tree frames (ordered).

Definition at line 561 of file robot.h.

◆ signature_

std::string se2ez::Robot::signature_
private

A string that represents the current kinematic chain.

Definition at line 573 of file robot.h.

◆ static_

FrameMapPtr se2ez::Robot::static_ {nullptr}
private

Transforms for all non-movable links.

Definition at line 576 of file robot.h.

◆ tree_

KDL::Tree se2ez::Robot::tree_
private

Underlying tree representation.

Definition at line 568 of file robot.h.

◆ tree_update_

bool se2ez::Robot::tree_update_ {true}
private

Does the tree need recompiling?

Definition at line 570 of file robot.h.

◆ upper_

Eigen::VectorXd se2ez::Robot::upper_
private

Upper limits of joints.

Definition at line 564 of file robot.h.


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