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
[legend]

Public Member Functions

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< 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)
 
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)
 
void ChangeParent (const std::string &name, const std::string &parent, const KDL::Frame &pose, bool relative)
 
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)
 
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
 
const Eigen::VectorXd & GetAccelerationLimits () const
 
std::map< std::string, shapes::ShapeTypeGetCollisionObjectTypes () const
 
const std::map< std::string, std::weak_ptr< KinematicElement > > & GetCollisionTreeMap () const
 
BaseType GetControlledBaseType () const
 
const std::vector< std::string > & GetControlledJointNames () const
 
const std::vector< std::weak_ptr< KinematicElement > > & GetControlledJoints () const
 
const std::map< std::string, std::weak_ptr< KinematicElement > > & GetControlledJointsMap () const
 
Eigen::VectorXd GetControlledLinkMass () const
 
const std::vector< std::string > & GetControlledLinkNames () const
 
Eigen::VectorXd GetControlledState () const
 
const Eigen::MatrixXd & GetJointLimits () 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...
 
std::shared_ptr< KinematicResponseGetKinematicResponse ()
 
BaseType GetModelBaseType () const
 
const std::vector< std::string > & GetModelJointNames () const
 
const std::map< std::string, std::weak_ptr< KinematicElement > > & GetModelJointsMap () const
 
const std::vector< std::string > & GetModelLinkNames () const
 
Eigen::VectorXd GetModelState () const
 
std::map< std::string, double > GetModelStateMap () const
 
const std::vector< std::shared_ptr< KinematicElement > > & GetModelTree () const
 
int GetNumControlledJoints () const
 
int GetNumModelJoints () const
 
Eigen::VectorXd GetRandomControlledState ()
 Random state generation. More...
 
robot_model::RobotModelPtr GetRobotModel () const
 
const std::string & GetRootFrameName () const
 
const std::string & GetRootJointName () const
 
const std::vector< std::weak_ptr< KinematicElement > > & GetTree () const
 
const std::map< std::string, std::weak_ptr< KinematicElement > > & GetTreeMap () const
 
std::map< std::string, std::vector< double > > GetUsedJointLimits () const
 
const Eigen::VectorXd & GetVelocityLimits () const
 
const bool & HasAccelerationLimits () const
 
bool HasModelLink (const std::string &link) 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 Instantiate (const std::string &joint_group, robot_model::RobotModelPtr model, const std::string &name)
 
int IsControlled (std::shared_ptr< KinematicElement > joint)
 
int IsControlledLink (const std::string &link_name)
 
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
 
void PublishFrames (const std::string &tf_prefix="exotica")
 
std::shared_ptr< KinematicResponseRequestFrames (const KinematicsRequest &request)
 
void ResetJointLimits ()
 
void ResetModel ()
 
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 SetJointAccelerationLimits (Eigen::VectorXdRefConst acceleration_in)
 
void SetJointLimitsLower (Eigen::VectorXdRefConst lower_in)
 
void SetJointLimitsUpper (Eigen::VectorXdRefConst upper_in)
 
void SetJointVelocityLimits (Eigen::VectorXdRefConst velocity_in)
 
void SetKinematicResponse (std::shared_ptr< KinematicResponse > response_in)
 
void SetModelState (Eigen::VectorXdRefConst x)
 
void SetModelState (const std::map< std::string, double > &x)
 
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)
 
void SetSeed (const uint_fast32_t seed)
 SetSeed sets the seed of the random generator for deterministic joint state sampling. More...
 
void Update (Eigen::VectorXdRefConst x)
 
void UpdateModel ()
 
- Public Member Functions inherited from exotica::Uncopyable
 Uncopyable ()=default
 
 ~Uncopyable ()=default
 

Public Attributes

bool debug = false
 

Private Member Functions

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

Private Attributes

Eigen::VectorXd acceleration_limits_
 
std::map< std::string, std::weak_ptr< KinematicElement > > collision_tree_map_
 
BaseType controlled_base_type_ = BaseType::FIXED
 
std::vector< std::weak_ptr< KinematicElement > > controlled_joints_
 
std::map< std::string, std::weak_ptr< KinematicElement > > controlled_joints_map_
 
std::vector< std::string > controlled_joints_names_
 
std::vector< std::string > controlled_link_names_
 
std::vector< tf::StampedTransformdebug_frames_
 
bool debug_scene_changed_
 
std::vector< tf::StampedTransformdebug_tree_
 
std::vector< std::shared_ptr< KinematicElement > > environment_tree_
 
KinematicRequestFlags flags_
 
std::mt19937 generator_
 
bool has_acceleration_limit_ = false
 
Eigen::MatrixXd joint_limits_
 
visualization_msgs::MarkerArray marker_array_msg_
 
robot_model::RobotModelPtr model_
 
BaseType model_base_type_
 
std::map< std::string, std::weak_ptr< KinematicElement > > model_joints_map_
 
std::vector< std::string > model_joints_names_
 
std::vector< std::string > model_link_names_
 
std::vector< std::shared_ptr< KinematicElement > > model_tree_
 
std::string name_
 
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...
 
ros::Publisher octomap_pub_
 
std::vector< std::uniform_real_distribution< double > > random_state_distributions_
 
std::random_device rd_
 
std::shared_ptr< KinematicElementroot_
 
std::string root_joint_name_ = ""
 
ros::Publisher shapes_pub_
 
std::shared_ptr< KinematicResponsesolution_ = std::make_shared<KinematicResponse>()
 
int state_size_ = -1
 
std::vector< std::weak_ptr< KinematicElement > > tree_
 
std::map< std::string, std::weak_ptr< KinematicElement > > tree_map_
 
Eigen::VectorXd tree_state_
 
Eigen::VectorXd velocity_limits_
 

Detailed Description

Definition at line 142 of file kinematic_tree.h.

Member Function Documentation

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 
)

Definition at line 517 of file kinematic_tree.cpp.

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 
)

Definition at line 489 of file kinematic_tree.cpp.

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

Definition at line 560 of file kinematic_tree.cpp.

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 
)

Definition at line 482 of file kinematic_tree.cpp.

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

Definition at line 164 of file kinematic_tree.cpp.

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

Definition at line 434 of file kinematic_tree.cpp.

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

Definition at line 920 of file kinematic_tree.cpp.

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

Definition at line 892 of file kinematic_tree.cpp.

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

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

Definition at line 1416 of file kinematic_tree.cpp.

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

Definition at line 1422 of file kinematic_tree.cpp.

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

Definition at line 802 of file kinematic_tree.cpp.

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

Definition at line 810 of file kinematic_tree.cpp.

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

Definition at line 821 of file kinematic_tree.cpp.

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

Definition at line 165 of file kinematic_tree.h.

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

Definition at line 1406 of file kinematic_tree.cpp.

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

Definition at line 234 of file kinematic_tree.h.

exotica::BaseType exotica::KinematicTree::GetControlledBaseType ( ) const

Definition at line 978 of file kinematic_tree.cpp.

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

Definition at line 171 of file kinematic_tree.h.

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

Definition at line 238 of file kinematic_tree.h.

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

Definition at line 239 of file kinematic_tree.h.

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

Definition at line 1396 of file kinematic_tree.cpp.

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

Definition at line 176 of file kinematic_tree.h.

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

Definition at line 1381 of file kinematic_tree.cpp.

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

Definition at line 154 of file kinematic_tree.h.

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

Definition at line 1287 of file kinematic_tree.cpp.

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

Definition at line 1315 of file kinematic_tree.cpp.

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

Definition at line 250 of file kinematic_tree.h.

exotica::BaseType exotica::KinematicTree::GetModelBaseType ( ) const

Definition at line 973 of file kinematic_tree.cpp.

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

Definition at line 181 of file kinematic_tree.h.

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

Definition at line 240 of file kinematic_tree.h.

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

Definition at line 186 of file kinematic_tree.h.

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

Definition at line 1266 of file kinematic_tree.cpp.

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

Definition at line 1277 of file kinematic_tree.cpp.

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

Definition at line 232 of file kinematic_tree.h.

int exotica::KinematicTree::GetNumControlledJoints ( ) const

Definition at line 91 of file kinematic_tree.cpp.

int exotica::KinematicTree::GetNumModelJoints ( ) const

Definition at line 96 of file kinematic_tree.cpp.

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

Random state generation.

Definition at line 998 of file kinematic_tree.cpp.

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

Definition at line 993 of file kinematic_tree.cpp.

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

Definition at line 1256 of file kinematic_tree.cpp.

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

Definition at line 1261 of file kinematic_tree.cpp.

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

Definition at line 231 of file kinematic_tree.h.

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

Definition at line 233 of file kinematic_tree.h.

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

Definition at line 983 of file kinematic_tree.cpp.

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

Definition at line 166 of file kinematic_tree.h.

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

Definition at line 164 of file kinematic_tree.h.

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

Definition at line 1391 of file kinematic_tree.cpp.

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

Definition at line 866 of file kinematic_tree.cpp.

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

Definition at line 881 of file kinematic_tree.cpp.

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

Definition at line 101 of file kinematic_tree.cpp.

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

Definition at line 571 of file kinematic_tree.cpp.

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

Definition at line 580 of file kinematic_tree.cpp.

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

Definition at line 842 of file kinematic_tree.cpp.

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

Definition at line 855 of file kinematic_tree.cpp.

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

Definition at line 712 of file kinematic_tree.cpp.

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

Definition at line 608 of file kinematic_tree.cpp.

void exotica::KinematicTree::ResetJointLimits ( )

Manually defined floating base limits Should be done more systematically with robot model class

Definition at line 1174 of file kinematic_tree.cpp.

void exotica::KinematicTree::ResetModel ( )

Definition at line 416 of file kinematic_tree.cpp.

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

Definition at line 1078 of file kinematic_tree.cpp.

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

Definition at line 1097 of file kinematic_tree.cpp.

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

Definition at line 1059 of file kinematic_tree.cpp.

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

Definition at line 1008 of file kinematic_tree.cpp.

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

Definition at line 1025 of file kinematic_tree.cpp.

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

Definition at line 1042 of file kinematic_tree.cpp.

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

Definition at line 249 of file kinematic_tree.h.

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

Definition at line 1342 of file kinematic_tree.cpp.

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

Definition at line 1362 of file kinematic_tree.cpp.

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

Definition at line 1126 of file kinematic_tree.cpp.

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

Definition at line 1145 of file kinematic_tree.cpp.

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

Definition at line 245 of file kinematic_tree.h.

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

Definition at line 658 of file kinematic_tree.cpp.

void exotica::KinematicTree::UpdateFK ( )
private

Definition at line 832 of file kinematic_tree.cpp.

void exotica::KinematicTree::UpdateH ( )
private

Definition at line 963 of file kinematic_tree.cpp.

void exotica::KinematicTree::UpdateJ ( )
private

Definition at line 953 of file kinematic_tree.cpp.

void exotica::KinematicTree::UpdateJointLimits ( )
private

Definition at line 1236 of file kinematic_tree.cpp.

void exotica::KinematicTree::UpdateModel ( )

Definition at line 403 of file kinematic_tree.cpp.

void exotica::KinematicTree::UpdateTree ( )
private

Definition at line 675 of file kinematic_tree.cpp.

Member Data Documentation

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

Definition at line 267 of file kinematic_tree.h.

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

Definition at line 288 of file kinematic_tree.h.

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

Definition at line 277 of file kinematic_tree.h.

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

Definition at line 290 of file kinematic_tree.h.

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

Definition at line 291 of file kinematic_tree.h.

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

Definition at line 294 of file kinematic_tree.h.

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

Definition at line 296 of file kinematic_tree.h.

bool exotica::KinematicTree::debug = false

Definition at line 251 of file kinematic_tree.h.

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

Definition at line 301 of file kinematic_tree.h.

bool exotica::KinematicTree::debug_scene_changed_
private

Definition at line 304 of file kinematic_tree.h.

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

Definition at line 300 of file kinematic_tree.h.

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

Definition at line 286 of file kinematic_tree.h.

KinematicRequestFlags exotica::KinematicTree::flags_
private

Definition at line 298 of file kinematic_tree.h.

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

Definition at line 273 of file kinematic_tree.h.

bool exotica::KinematicTree::has_acceleration_limit_ = false
private

Definition at line 268 of file kinematic_tree.h.

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

Definition at line 265 of file kinematic_tree.h.

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

Definition at line 305 of file kinematic_tree.h.

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

Definition at line 282 of file kinematic_tree.h.

BaseType exotica::KinematicTree::model_base_type_
private

Definition at line 276 of file kinematic_tree.h.

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

Definition at line 292 of file kinematic_tree.h.

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

Definition at line 293 of file kinematic_tree.h.

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

Definition at line 295 of file kinematic_tree.h.

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

Definition at line 285 of file kinematic_tree.h.

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

Definition at line 306 of file kinematic_tree.h.

int exotica::KinematicTree::num_controlled_joints_
private

Number of controlled joints in the joint group.

Definition at line 278 of file kinematic_tree.h.

int exotica::KinematicTree::num_joints_
private

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

Definition at line 279 of file kinematic_tree.h.

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

Definition at line 303 of file kinematic_tree.h.

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

Definition at line 274 of file kinematic_tree.h.

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

Definition at line 272 of file kinematic_tree.h.

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

Definition at line 289 of file kinematic_tree.h.

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

Definition at line 283 of file kinematic_tree.h.

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

Definition at line 302 of file kinematic_tree.h.

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

Definition at line 297 of file kinematic_tree.h.

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

Definition at line 280 of file kinematic_tree.h.

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

Definition at line 284 of file kinematic_tree.h.

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

Definition at line 287 of file kinematic_tree.h.

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

Definition at line 281 of file kinematic_tree.h.

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

Definition at line 266 of file kinematic_tree.h.


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


exotica_core
Author(s): Yiming Yang, Michael Camilleri
autogenerated on Sat Apr 10 2021 02:34:50