Exotica
Public Member Functions | Public Attributes | Private Member Functions | Private Attributes | List of all members
exotica::KinematicTree Class Reference

#include <kinematic_tree.h>

Inheritance diagram for exotica::KinematicTree:
Inheritance graph
Collaboration diagram for exotica::KinematicTree:
Collaboration graph

Public Member Functions

void Instantiate (const std::string &joint_group, robot_model::RobotModelPtr model, const std::string &name)
 
const std::string & GetRootFrameName () const
 
const std::string & GetRootJointName () const
 
robot_model::RobotModelPtr GetRobotModel () const
 
BaseType GetModelBaseType () const
 
BaseType GetControlledBaseType () const
 
std::shared_ptr< KinematicResponseRequestFrames (const KinematicsRequest &request)
 
void Update (Eigen::VectorXdRefConst x)
 
void ResetJointLimits ()
 
const Eigen::MatrixXd & GetJointLimits () const
 
void SetJointLimitsLower (Eigen::VectorXdRefConst lower_in)
 
void SetJointLimitsUpper (Eigen::VectorXdRefConst upper_in)
 
void SetJointVelocityLimits (Eigen::VectorXdRefConst velocity_in)
 
void SetJointAccelerationLimits (Eigen::VectorXdRefConst acceleration_in)
 
void SetFloatingBaseLimitsPosXYZEulerZYX (const std::vector< double > &lower, const std::vector< double > &upper)
 
void SetFloatingBaseLimitsPosXYZEulerZYX (const std::vector< double > &lower, const std::vector< double > &upper, const std::vector< double > &velocity, const std::vector< double > &acceleration)
 
void SetPlanarBaseLimitsPosXYEulerZ (const std::vector< double > &lower, const std::vector< double > &upper)
 
void SetPlanarBaseLimitsPosXYEulerZ (const std::vector< double > &lower, const std::vector< double > &upper, const std::vector< double > &velocity, const std::vector< double > &acceleration)
 
std::map< std::string, std::vector< double > > GetUsedJointLimits () const
 
const bool & HasAccelerationLimits () const
 
const Eigen::VectorXd & GetAccelerationLimits () const
 
const Eigen::VectorXd & GetVelocityLimits () const
 
int GetNumControlledJoints () const
 
int GetNumModelJoints () const
 
void PublishFrames (const std::string &tf_prefix="exotica")
 
const std::vector< std::string > & GetControlledJointNames () const
 
const std::vector< std::string > & GetControlledLinkNames () const
 
const std::vector< std::string > & GetModelJointNames () const
 
const std::vector< std::string > & GetModelLinkNames () const
 
bool HasModelLink (const std::string &link) const
 
Eigen::VectorXd GetControlledLinkMass () const
 
KDL::Frame FK (KinematicFrame &frame) const
 
KDL::Frame FK (std::shared_ptr< KinematicElement > element_A, const KDL::Frame &offset_a, std::shared_ptr< KinematicElement > element_B, const KDL::Frame &offset_b) const
 
KDL::Frame FK (const std::string &element_A, const KDL::Frame &offset_a, const std::string &element_B, const KDL::Frame &offset_b) const
 
Eigen::MatrixXd Jacobian (std::shared_ptr< KinematicElement > element_A, const KDL::Frame &offset_a, std::shared_ptr< KinematicElement > element_B, const KDL::Frame &offset_b) const
 
Eigen::MatrixXd Jacobian (const std::string &element_A, const KDL::Frame &offset_a, const std::string &element_B, const KDL::Frame &offset_b) const
 
exotica::Hessian Hessian (std::shared_ptr< KinematicElement > element_A, const KDL::Frame &offset_a, std::shared_ptr< KinematicElement > element_B, const KDL::Frame &offset_b) const
 
exotica::Hessian Hessian (const std::string &element_A, const KDL::Frame &offset_a, const std::string &element_B, const KDL::Frame &offset_b) const
 
void ResetModel ()
 
std::shared_ptr< KinematicElementAddElement (const std::string &name, const Eigen::Isometry3d &transform, const std::string &parent="", shapes::ShapeConstPtr shape=shapes::ShapeConstPtr(nullptr), const KDL::RigidBodyInertia &inertia=KDL::RigidBodyInertia::Zero(), const Eigen::Vector4d &color=Eigen::Vector4d(0.5, 0.5, 0.5, 1.0), const std::vector< VisualElement > &visual={}, bool is_controlled=false)
 
std::shared_ptr< KinematicElementAddEnvironmentElement (const std::string &name, const Eigen::Isometry3d &transform, const std::string &parent="", shapes::ShapeConstPtr shape=shapes::ShapeConstPtr(nullptr), const KDL::RigidBodyInertia &inertia=KDL::RigidBodyInertia::Zero(), const Eigen::Vector4d &color=Eigen::Vector4d(0.5, 0.5, 0.5, 1.0), const std::vector< VisualElement > &visual={}, bool is_controlled=false)
 
std::shared_ptr< KinematicElementAddElement (const std::string &name, const Eigen::Isometry3d &transform, const std::string &parent, const std::string &shape_resource_path, Eigen::Vector3d scale=Eigen::Vector3d::Ones(), const KDL::RigidBodyInertia &inertia=KDL::RigidBodyInertia::Zero(), const Eigen::Vector4d &color=Eigen::Vector4d(0.5, 0.5, 0.5, 1.0), const std::vector< VisualElement > &visual={}, bool is_controlled=false)
 
void UpdateModel ()
 
void ChangeParent (const std::string &name, const std::string &parent, const KDL::Frame &pose, bool relative)
 
int IsControlled (std::shared_ptr< KinematicElement > joint)
 
int IsControlledLink (const std::string &link_name)
 
Eigen::VectorXd GetModelState () const
 
std::map< std::string, double > GetModelStateMap () const
 
std::vector< std::string > GetKinematicChain (const std::string &begin, const std::string &end) const
 GetKinematicChain get list of joints in a kinematic chain. More...
 
std::vector< std::string > GetKinematicChainLinks (const std::string &begin, const std::string &end) const
 GetKinematicChainLinks get the links between begin and end of kinematic chain. More...
 
void SetModelState (Eigen::VectorXdRefConst x)
 
void SetModelState (const std::map< std::string, double > &x)
 
Eigen::VectorXd GetControlledState () const
 
const std::vector< std::weak_ptr< KinematicElement > > & GetTree () const
 
const std::vector< std::shared_ptr< KinematicElement > > & GetModelTree () const
 
const std::map< std::string, std::weak_ptr< KinematicElement > > & GetTreeMap () const
 
const std::map< std::string, std::weak_ptr< KinematicElement > > & GetCollisionTreeMap () const
 
bool DoesLinkWithNameExist (std::string name) const
 Checks whether a link with this name exists in any of the trees. More...
 
std::shared_ptr< KinematicElementFindKinematicElementByName (const std::string &frame_name)
 
const std::vector< std::weak_ptr< KinematicElement > > & GetControlledJoints () const
 
const std::map< std::string, std::weak_ptr< KinematicElement > > & GetControlledJointsMap () const
 
const std::map< std::string, std::weak_ptr< KinematicElement > > & GetModelJointsMap () const
 
std::map< std::string, shapes::ShapeType > GetCollisionObjectTypes () const
 
void SetSeed (const uint_fast32_t seed)
 SetSeed sets the seed of the random generator for deterministic joint state sampling. More...
 
Eigen::VectorXd GetRandomControlledState ()
 Random state generation. More...
 
void SetKinematicResponse (std::shared_ptr< KinematicResponse > response_in)
 
std::shared_ptr< KinematicResponseGetKinematicResponse ()
 
- Public Member Functions inherited from exotica::Uncopyable
 Uncopyable ()=default
 
 ~Uncopyable ()=default
 

Public Attributes

bool debug = false
 

Private Member Functions

void BuildTree (const KDL::Tree &RobotKinematics)
 
void AddElementFromSegmentMapIterator (KDL::SegmentMap::const_iterator segment, std::shared_ptr< KinematicElement > parent)
 
void UpdateTree ()
 
void UpdateFK ()
 
void UpdateJ ()
 
void ComputeJ (KinematicFrame &frame, KDL::Jacobian &jacobian) const
 
void UpdateH ()
 
void ComputeH (KinematicFrame &frame, const KDL::Jacobian &jacobian, exotica::Hessian &hessian) const
 
void UpdateJointLimits ()
 

Private Attributes

Eigen::MatrixXd joint_limits_
 
Eigen::VectorXd velocity_limits_
 
Eigen::VectorXd acceleration_limits_
 
bool has_acceleration_limit_ = false
 
std::random_device rd_
 
std::mt19937 generator_
 
std::vector< std::uniform_real_distribution< double > > random_state_distributions_
 
BaseType model_base_type_
 
BaseType controlled_base_type_ = BaseType::FIXED
 
int num_controlled_joints_
 Number of controlled joints in the joint group. More...
 
int num_joints_
 Number of joints of the model (including floating/planar base, passive joints, and uncontrolled joints). More...
 
int state_size_ = -1
 
Eigen::VectorXd tree_state_
 
robot_model::RobotModelPtr model_
 
std::string root_joint_name_ = ""
 
std::vector< std::weak_ptr< KinematicElement > > tree_
 
std::vector< std::shared_ptr< KinematicElement > > model_tree_
 
std::vector< std::shared_ptr< KinematicElement > > environment_tree_
 
std::map< std::string, std::weak_ptr< KinematicElement > > tree_map_
 
std::map< std::string, std::weak_ptr< KinematicElement > > collision_tree_map_
 
std::shared_ptr< KinematicElementroot_
 
std::vector< std::weak_ptr< KinematicElement > > controlled_joints_
 
std::map< std::string, std::weak_ptr< KinematicElement > > controlled_joints_map_
 
std::map< std::string, std::weak_ptr< KinematicElement > > model_joints_map_
 
std::vector< std::string > model_joints_names_
 
std::vector< std::string > controlled_joints_names_
 
std::vector< std::string > model_link_names_
 
std::vector< std::string > controlled_link_names_
 
std::shared_ptr< KinematicResponsesolution_ = std::make_shared<KinematicResponse>()
 
KinematicRequestFlags flags_
 
std::vector< tf::StampedTransform > debug_tree_
 
std::vector< tf::StampedTransform > debug_frames_
 
ros::Publisher shapes_pub_
 
ros::Publisher octomap_pub_
 
bool debug_scene_changed_
 
visualization_msgs::MarkerArray marker_array_msg_
 
std::string name_
 

Member Function Documentation

◆ AddElement() [1/2]

std::shared_ptr<KinematicElement> exotica::KinematicTree::AddElement ( const std::string &  name,
const Eigen::Isometry3d &  transform,
const std::string &  parent,
const std::string &  shape_resource_path,
Eigen::Vector3d  scale = Eigen::Vector3d::Ones(),
const KDL::RigidBodyInertia &  inertia = KDL::RigidBodyInertia::Zero(),
const Eigen::Vector4d &  color = Eigen::Vector4d(0.5, 0.5, 0.5, 1.0),
const std::vector< VisualElement > &  visual = {},
bool  is_controlled = false 
)

◆ AddElement() [2/2]

std::shared_ptr<KinematicElement> exotica::KinematicTree::AddElement ( const std::string &  name,
const Eigen::Isometry3d &  transform,
const std::string &  parent = "",
shapes::ShapeConstPtr  shape = shapes::ShapeConstPtr(nullptr),
const KDL::RigidBodyInertia &  inertia = KDL::RigidBodyInertia::Zero(),
const Eigen::Vector4d &  color = Eigen::Vector4d(0.5, 0.5, 0.5, 1.0),
const std::vector< VisualElement > &  visual = {},
bool  is_controlled = false 
)

◆ AddElementFromSegmentMapIterator()

void exotica::KinematicTree::AddElementFromSegmentMapIterator ( KDL::SegmentMap::const_iterator  segment,
std::shared_ptr< KinematicElement parent 
)
private

◆ AddEnvironmentElement()

std::shared_ptr<KinematicElement> exotica::KinematicTree::AddEnvironmentElement ( const std::string &  name,
const Eigen::Isometry3d &  transform,
const std::string &  parent = "",
shapes::ShapeConstPtr  shape = shapes::ShapeConstPtr(nullptr),
const KDL::RigidBodyInertia &  inertia = KDL::RigidBodyInertia::Zero(),
const Eigen::Vector4d &  color = Eigen::Vector4d(0.5, 0.5, 0.5, 1.0),
const std::vector< VisualElement > &  visual = {},
bool  is_controlled = false 
)

◆ BuildTree()

void exotica::KinematicTree::BuildTree ( const KDL::Tree &  RobotKinematics)
private

◆ ChangeParent()

void exotica::KinematicTree::ChangeParent ( const std::string &  name,
const std::string &  parent,
const KDL::Frame &  pose,
bool  relative 
)

◆ ComputeH()

void exotica::KinematicTree::ComputeH ( KinematicFrame frame,
const KDL::Jacobian &  jacobian,
exotica::Hessian hessian 
) const
private

◆ ComputeJ()

void exotica::KinematicTree::ComputeJ ( KinematicFrame frame,
KDL::Jacobian &  jacobian 
) const
private

◆ DoesLinkWithNameExist()

bool exotica::KinematicTree::DoesLinkWithNameExist ( std::string  name) const

Checks whether a link with this name exists in any of the trees.

◆ FindKinematicElementByName()

std::shared_ptr<KinematicElement> exotica::KinematicTree::FindKinematicElementByName ( const std::string &  frame_name)

◆ FK() [1/3]

KDL::Frame exotica::KinematicTree::FK ( const std::string &  element_A,
const KDL::Frame &  offset_a,
const std::string &  element_B,
const KDL::Frame &  offset_b 
) const

◆ FK() [2/3]

KDL::Frame exotica::KinematicTree::FK ( KinematicFrame frame) const

◆ FK() [3/3]

KDL::Frame exotica::KinematicTree::FK ( std::shared_ptr< KinematicElement element_A,
const KDL::Frame &  offset_a,
std::shared_ptr< KinematicElement element_B,
const KDL::Frame &  offset_b 
) const

◆ GetAccelerationLimits()

const Eigen::VectorXd& exotica::KinematicTree::GetAccelerationLimits ( ) const
inline

◆ GetCollisionObjectTypes()

std::map<std::string, shapes::ShapeType> exotica::KinematicTree::GetCollisionObjectTypes ( ) const

◆ GetCollisionTreeMap()

const std::map<std::string, std::weak_ptr<KinematicElement> >& exotica::KinematicTree::GetCollisionTreeMap ( ) const
inline

◆ GetControlledBaseType()

BaseType exotica::KinematicTree::GetControlledBaseType ( ) const

◆ GetControlledJointNames()

const std::vector<std::string>& exotica::KinematicTree::GetControlledJointNames ( ) const
inline

◆ GetControlledJoints()

const std::vector<std::weak_ptr<KinematicElement> >& exotica::KinematicTree::GetControlledJoints ( ) const
inline

◆ GetControlledJointsMap()

const std::map<std::string, std::weak_ptr<KinematicElement> >& exotica::KinematicTree::GetControlledJointsMap ( ) const
inline

◆ GetControlledLinkMass()

Eigen::VectorXd exotica::KinematicTree::GetControlledLinkMass ( ) const

◆ GetControlledLinkNames()

const std::vector<std::string>& exotica::KinematicTree::GetControlledLinkNames ( ) const
inline

◆ GetControlledState()

Eigen::VectorXd exotica::KinematicTree::GetControlledState ( ) const

◆ GetJointLimits()

const Eigen::MatrixXd& exotica::KinematicTree::GetJointLimits ( ) const
inline

◆ GetKinematicChain()

std::vector<std::string> exotica::KinematicTree::GetKinematicChain ( const std::string &  begin,
const std::string &  end 
) const

GetKinematicChain get list of joints in a kinematic chain.

Parameters
beginlink name from which the chain starts
endlink name at which the chain ends
Returns
list joints between begin and end

◆ GetKinematicChainLinks()

std::vector<std::string> exotica::KinematicTree::GetKinematicChainLinks ( const std::string &  begin,
const std::string &  end 
) const

GetKinematicChainLinks get the links between begin and end of kinematic chain.

Parameters
beginlink name from which the chain starts
endlink name at which the chain ends
Returns
list link between begin and end

◆ GetKinematicResponse()

std::shared_ptr<KinematicResponse> exotica::KinematicTree::GetKinematicResponse ( )
inline

◆ GetModelBaseType()

BaseType exotica::KinematicTree::GetModelBaseType ( ) const

◆ GetModelJointNames()

const std::vector<std::string>& exotica::KinematicTree::GetModelJointNames ( ) const
inline

◆ GetModelJointsMap()

const std::map<std::string, std::weak_ptr<KinematicElement> >& exotica::KinematicTree::GetModelJointsMap ( ) const
inline

◆ GetModelLinkNames()

const std::vector<std::string>& exotica::KinematicTree::GetModelLinkNames ( ) const
inline

◆ GetModelState()

Eigen::VectorXd exotica::KinematicTree::GetModelState ( ) const

◆ GetModelStateMap()

std::map<std::string, double> exotica::KinematicTree::GetModelStateMap ( ) const

◆ GetModelTree()

const std::vector<std::shared_ptr<KinematicElement> >& exotica::KinematicTree::GetModelTree ( ) const
inline

◆ GetNumControlledJoints()

int exotica::KinematicTree::GetNumControlledJoints ( ) const

◆ GetNumModelJoints()

int exotica::KinematicTree::GetNumModelJoints ( ) const

◆ GetRandomControlledState()

Eigen::VectorXd exotica::KinematicTree::GetRandomControlledState ( )

Random state generation.

◆ GetRobotModel()

robot_model::RobotModelPtr exotica::KinematicTree::GetRobotModel ( ) const

◆ GetRootFrameName()

const std::string& exotica::KinematicTree::GetRootFrameName ( ) const

◆ GetRootJointName()

const std::string& exotica::KinematicTree::GetRootJointName ( ) const

◆ GetTree()

const std::vector<std::weak_ptr<KinematicElement> >& exotica::KinematicTree::GetTree ( ) const
inline

◆ GetTreeMap()

const std::map<std::string, std::weak_ptr<KinematicElement> >& exotica::KinematicTree::GetTreeMap ( ) const
inline

◆ GetUsedJointLimits()

std::map<std::string, std::vector<double> > exotica::KinematicTree::GetUsedJointLimits ( ) const

◆ GetVelocityLimits()

const Eigen::VectorXd& exotica::KinematicTree::GetVelocityLimits ( ) const
inline

◆ HasAccelerationLimits()

const bool& exotica::KinematicTree::HasAccelerationLimits ( ) const
inline

◆ HasModelLink()

bool exotica::KinematicTree::HasModelLink ( const std::string &  link) const

◆ Hessian() [1/2]

exotica::Hessian exotica::KinematicTree::Hessian ( const std::string &  element_A,
const KDL::Frame &  offset_a,
const std::string &  element_B,
const KDL::Frame &  offset_b 
) const

◆ Hessian() [2/2]

exotica::Hessian exotica::KinematicTree::Hessian ( std::shared_ptr< KinematicElement element_A,
const KDL::Frame &  offset_a,
std::shared_ptr< KinematicElement element_B,
const KDL::Frame &  offset_b 
) const

◆ Instantiate()

void exotica::KinematicTree::Instantiate ( const std::string &  joint_group,
robot_model::RobotModelPtr  model,
const std::string &  name 
)

◆ IsControlled()

int exotica::KinematicTree::IsControlled ( std::shared_ptr< KinematicElement joint)

◆ IsControlledLink()

int exotica::KinematicTree::IsControlledLink ( const std::string &  link_name)

◆ Jacobian() [1/2]

Eigen::MatrixXd exotica::KinematicTree::Jacobian ( const std::string &  element_A,
const KDL::Frame &  offset_a,
const std::string &  element_B,
const KDL::Frame &  offset_b 
) const

◆ Jacobian() [2/2]

Eigen::MatrixXd exotica::KinematicTree::Jacobian ( std::shared_ptr< KinematicElement element_A,
const KDL::Frame &  offset_a,
std::shared_ptr< KinematicElement element_B,
const KDL::Frame &  offset_b 
) const

◆ PublishFrames()

void exotica::KinematicTree::PublishFrames ( const std::string &  tf_prefix = "exotica")

◆ RequestFrames()

std::shared_ptr<KinematicResponse> exotica::KinematicTree::RequestFrames ( const KinematicsRequest request)

◆ ResetJointLimits()

void exotica::KinematicTree::ResetJointLimits ( )

◆ ResetModel()

void exotica::KinematicTree::ResetModel ( )

◆ SetFloatingBaseLimitsPosXYZEulerZYX() [1/2]

void exotica::KinematicTree::SetFloatingBaseLimitsPosXYZEulerZYX ( const std::vector< double > &  lower,
const std::vector< double > &  upper 
)

◆ SetFloatingBaseLimitsPosXYZEulerZYX() [2/2]

void exotica::KinematicTree::SetFloatingBaseLimitsPosXYZEulerZYX ( const std::vector< double > &  lower,
const std::vector< double > &  upper,
const std::vector< double > &  velocity,
const std::vector< double > &  acceleration 
)

◆ SetJointAccelerationLimits()

void exotica::KinematicTree::SetJointAccelerationLimits ( Eigen::VectorXdRefConst  acceleration_in)

◆ SetJointLimitsLower()

void exotica::KinematicTree::SetJointLimitsLower ( Eigen::VectorXdRefConst  lower_in)

◆ SetJointLimitsUpper()

void exotica::KinematicTree::SetJointLimitsUpper ( Eigen::VectorXdRefConst  upper_in)

◆ SetJointVelocityLimits()

void exotica::KinematicTree::SetJointVelocityLimits ( Eigen::VectorXdRefConst  velocity_in)

◆ SetKinematicResponse()

void exotica::KinematicTree::SetKinematicResponse ( std::shared_ptr< KinematicResponse response_in)
inline

◆ SetModelState() [1/2]

void exotica::KinematicTree::SetModelState ( const std::map< std::string, double > &  x)

◆ SetModelState() [2/2]

void exotica::KinematicTree::SetModelState ( Eigen::VectorXdRefConst  x)

◆ SetPlanarBaseLimitsPosXYEulerZ() [1/2]

void exotica::KinematicTree::SetPlanarBaseLimitsPosXYEulerZ ( const std::vector< double > &  lower,
const std::vector< double > &  upper 
)

◆ SetPlanarBaseLimitsPosXYEulerZ() [2/2]

void exotica::KinematicTree::SetPlanarBaseLimitsPosXYEulerZ ( const std::vector< double > &  lower,
const std::vector< double > &  upper,
const std::vector< double > &  velocity,
const std::vector< double > &  acceleration 
)

◆ SetSeed()

void exotica::KinematicTree::SetSeed ( const uint_fast32_t  seed)
inline

SetSeed sets the seed of the random generator for deterministic joint state sampling.

Parameters
seedunsigned integer

◆ Update()

void exotica::KinematicTree::Update ( Eigen::VectorXdRefConst  x)

◆ UpdateFK()

void exotica::KinematicTree::UpdateFK ( )
private

◆ UpdateH()

void exotica::KinematicTree::UpdateH ( )
private

◆ UpdateJ()

void exotica::KinematicTree::UpdateJ ( )
private

◆ UpdateJointLimits()

void exotica::KinematicTree::UpdateJointLimits ( )
private

◆ UpdateModel()

void exotica::KinematicTree::UpdateModel ( )

◆ UpdateTree()

void exotica::KinematicTree::UpdateTree ( )
private

Member Data Documentation

◆ acceleration_limits_

Eigen::VectorXd exotica::KinematicTree::acceleration_limits_
private

◆ collision_tree_map_

std::map<std::string, std::weak_ptr<KinematicElement> > exotica::KinematicTree::collision_tree_map_
private

◆ controlled_base_type_

BaseType exotica::KinematicTree::controlled_base_type_ = BaseType::FIXED
private

◆ controlled_joints_

std::vector<std::weak_ptr<KinematicElement> > exotica::KinematicTree::controlled_joints_
private

◆ controlled_joints_map_

std::map<std::string, std::weak_ptr<KinematicElement> > exotica::KinematicTree::controlled_joints_map_
private

◆ controlled_joints_names_

std::vector<std::string> exotica::KinematicTree::controlled_joints_names_
private

◆ controlled_link_names_

std::vector<std::string> exotica::KinematicTree::controlled_link_names_
private

◆ debug

bool exotica::KinematicTree::debug = false

◆ debug_frames_

std::vector<tf::StampedTransform> exotica::KinematicTree::debug_frames_
private

◆ debug_scene_changed_

bool exotica::KinematicTree::debug_scene_changed_
private

◆ debug_tree_

std::vector<tf::StampedTransform> exotica::KinematicTree::debug_tree_
private

◆ environment_tree_

std::vector<std::shared_ptr<KinematicElement> > exotica::KinematicTree::environment_tree_
private

◆ flags_

KinematicRequestFlags exotica::KinematicTree::flags_
private

◆ generator_

std::mt19937 exotica::KinematicTree::generator_
private

◆ has_acceleration_limit_

bool exotica::KinematicTree::has_acceleration_limit_ = false
private

◆ joint_limits_

Eigen::MatrixXd exotica::KinematicTree::joint_limits_
private

◆ marker_array_msg_

visualization_msgs::MarkerArray exotica::KinematicTree::marker_array_msg_
private

◆ model_

robot_model::RobotModelPtr exotica::KinematicTree::model_
private

◆ model_base_type_

BaseType exotica::KinematicTree::model_base_type_
private

◆ model_joints_map_

std::map<std::string, std::weak_ptr<KinematicElement> > exotica::KinematicTree::model_joints_map_
private

◆ model_joints_names_

std::vector<std::string> exotica::KinematicTree::model_joints_names_
private

◆ model_link_names_

std::vector<std::string> exotica::KinematicTree::model_link_names_
private

◆ model_tree_

std::vector<std::shared_ptr<KinematicElement> > exotica::KinematicTree::model_tree_
private

◆ name_

std::string exotica::KinematicTree::name_
private

◆ num_controlled_joints_

int exotica::KinematicTree::num_controlled_joints_
private

Number of controlled joints in the joint group.

◆ num_joints_

int exotica::KinematicTree::num_joints_
private

Number of joints of the model (including floating/planar base, passive joints, and uncontrolled joints).

◆ octomap_pub_

ros::Publisher exotica::KinematicTree::octomap_pub_
private

◆ random_state_distributions_

std::vector<std::uniform_real_distribution<double> > exotica::KinematicTree::random_state_distributions_
private

◆ rd_

std::random_device exotica::KinematicTree::rd_
private

◆ root_

std::shared_ptr<KinematicElement> exotica::KinematicTree::root_
private

◆ root_joint_name_

std::string exotica::KinematicTree::root_joint_name_ = ""
private

◆ shapes_pub_

ros::Publisher exotica::KinematicTree::shapes_pub_
private

◆ solution_

std::shared_ptr<KinematicResponse> exotica::KinematicTree::solution_ = std::make_shared<KinematicResponse>()
private

◆ state_size_

int exotica::KinematicTree::state_size_ = -1
private

◆ tree_

std::vector<std::weak_ptr<KinematicElement> > exotica::KinematicTree::tree_
private

◆ tree_map_

std::map<std::string, std::weak_ptr<KinematicElement> > exotica::KinematicTree::tree_map_
private

◆ tree_state_

Eigen::VectorXd exotica::KinematicTree::tree_state_
private

◆ velocity_limits_

Eigen::VectorXd exotica::KinematicTree::velocity_limits_
private

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