exotica::KinematicTree Member List

This is the complete list of members for exotica::KinematicTree, including all inherited members.

acceleration_limits_exotica::KinematicTreeprivate
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)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)exotica::KinematicTree
AddElementFromSegmentMapIterator(KDL::SegmentMap::const_iterator segment, std::shared_ptr< KinematicElement > parent)exotica::KinematicTreeprivate
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)exotica::KinematicTree
BuildTree(const KDL::Tree &RobotKinematics)exotica::KinematicTreeprivate
ChangeParent(const std::string &name, const std::string &parent, const KDL::Frame &pose, bool relative)exotica::KinematicTree
collision_tree_map_exotica::KinematicTreeprivate
ComputeH(KinematicFrame &frame, const KDL::Jacobian &jacobian, exotica::Hessian &hessian) const exotica::KinematicTreeprivate
ComputeJ(KinematicFrame &frame, KDL::Jacobian &jacobian) const exotica::KinematicTreeprivate
controlled_base_type_exotica::KinematicTreeprivate
controlled_joints_exotica::KinematicTreeprivate
controlled_joints_map_exotica::KinematicTreeprivate
controlled_joints_names_exotica::KinematicTreeprivate
controlled_link_names_exotica::KinematicTreeprivate
debugexotica::KinematicTree
debug_frames_exotica::KinematicTreeprivate
debug_scene_changed_exotica::KinematicTreeprivate
debug_tree_exotica::KinematicTreeprivate
DoesLinkWithNameExist(std::string name) const exotica::KinematicTree
environment_tree_exotica::KinematicTreeprivate
FindKinematicElementByName(const std::string &frame_name)exotica::KinematicTree
FK(KinematicFrame &frame) const 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 exotica::KinematicTree
FK(const std::string &element_A, const KDL::Frame &offset_a, const std::string &element_B, const KDL::Frame &offset_b) const exotica::KinematicTree
flags_exotica::KinematicTreeprivate
generator_exotica::KinematicTreeprivate
GetAccelerationLimits() const exotica::KinematicTreeinline
GetCollisionObjectTypes() const exotica::KinematicTree
GetCollisionTreeMap() const exotica::KinematicTreeinline
GetControlledBaseType() const exotica::KinematicTree
GetControlledJointNames() const exotica::KinematicTreeinline
GetControlledJoints() const exotica::KinematicTreeinline
GetControlledJointsMap() const exotica::KinematicTreeinline
GetControlledLinkMass() const exotica::KinematicTree
GetControlledLinkNames() const exotica::KinematicTreeinline
GetControlledState() const exotica::KinematicTree
GetJointLimits() const exotica::KinematicTreeinline
GetKinematicChain(const std::string &begin, const std::string &end) const exotica::KinematicTree
GetKinematicChainLinks(const std::string &begin, const std::string &end) const exotica::KinematicTree
GetKinematicResponse()exotica::KinematicTreeinline
GetModelBaseType() const exotica::KinematicTree
GetModelJointNames() const exotica::KinematicTreeinline
GetModelJointsMap() const exotica::KinematicTreeinline
GetModelLinkNames() const exotica::KinematicTreeinline
GetModelState() const exotica::KinematicTree
GetModelStateMap() const exotica::KinematicTree
GetModelTree() const exotica::KinematicTreeinline
GetNumControlledJoints() const exotica::KinematicTree
GetNumModelJoints() const exotica::KinematicTree
GetRandomControlledState()exotica::KinematicTree
GetRobotModel() const exotica::KinematicTree
GetRootFrameName() const exotica::KinematicTree
GetRootJointName() const exotica::KinematicTree
GetTree() const exotica::KinematicTreeinline
GetTreeMap() const exotica::KinematicTreeinline
GetUsedJointLimits() const exotica::KinematicTree
GetVelocityLimits() const exotica::KinematicTreeinline
has_acceleration_limit_exotica::KinematicTreeprivate
HasAccelerationLimits() const exotica::KinematicTreeinline
HasModelLink(const std::string &link) const 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 exotica::KinematicTree
Hessian(const std::string &element_A, const KDL::Frame &offset_a, const std::string &element_B, const KDL::Frame &offset_b) const exotica::KinematicTree
Instantiate(const std::string &joint_group, robot_model::RobotModelPtr model, const std::string &name)exotica::KinematicTree
IsControlled(std::shared_ptr< KinematicElement > joint)exotica::KinematicTree
IsControlledLink(const std::string &link_name)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 exotica::KinematicTree
Jacobian(const std::string &element_A, const KDL::Frame &offset_a, const std::string &element_B, const KDL::Frame &offset_b) const exotica::KinematicTree
joint_limits_exotica::KinematicTreeprivate
marker_array_msg_exotica::KinematicTreeprivate
model_exotica::KinematicTreeprivate
model_base_type_exotica::KinematicTreeprivate
model_joints_map_exotica::KinematicTreeprivate
model_joints_names_exotica::KinematicTreeprivate
model_link_names_exotica::KinematicTreeprivate
model_tree_exotica::KinematicTreeprivate
name_exotica::KinematicTreeprivate
num_controlled_joints_exotica::KinematicTreeprivate
num_joints_exotica::KinematicTreeprivate
octomap_pub_exotica::KinematicTreeprivate
PublishFrames(const std::string &tf_prefix="exotica")exotica::KinematicTree
random_state_distributions_exotica::KinematicTreeprivate
rd_exotica::KinematicTreeprivate
RequestFrames(const KinematicsRequest &request)exotica::KinematicTree
ResetJointLimits()exotica::KinematicTree
ResetModel()exotica::KinematicTree
root_exotica::KinematicTreeprivate
root_joint_name_exotica::KinematicTreeprivate
SetFloatingBaseLimitsPosXYZEulerZYX(const std::vector< double > &lower, const std::vector< double > &upper)exotica::KinematicTree
SetFloatingBaseLimitsPosXYZEulerZYX(const std::vector< double > &lower, const std::vector< double > &upper, const std::vector< double > &velocity, const std::vector< double > &acceleration)exotica::KinematicTree
SetJointAccelerationLimits(Eigen::VectorXdRefConst acceleration_in)exotica::KinematicTree
SetJointLimitsLower(Eigen::VectorXdRefConst lower_in)exotica::KinematicTree
SetJointLimitsUpper(Eigen::VectorXdRefConst upper_in)exotica::KinematicTree
SetJointVelocityLimits(Eigen::VectorXdRefConst velocity_in)exotica::KinematicTree
SetKinematicResponse(std::shared_ptr< KinematicResponse > response_in)exotica::KinematicTreeinline
SetModelState(Eigen::VectorXdRefConst x)exotica::KinematicTree
SetModelState(const std::map< std::string, double > &x)exotica::KinematicTree
SetPlanarBaseLimitsPosXYEulerZ(const std::vector< double > &lower, const std::vector< double > &upper)exotica::KinematicTree
SetPlanarBaseLimitsPosXYEulerZ(const std::vector< double > &lower, const std::vector< double > &upper, const std::vector< double > &velocity, const std::vector< double > &acceleration)exotica::KinematicTree
SetSeed(const uint_fast32_t seed)exotica::KinematicTreeinline
shapes_pub_exotica::KinematicTreeprivate
solution_exotica::KinematicTreeprivate
state_size_exotica::KinematicTreeprivate
tree_exotica::KinematicTreeprivate
tree_map_exotica::KinematicTreeprivate
tree_state_exotica::KinematicTreeprivate
Uncopyable()=defaultexotica::Uncopyable
Update(Eigen::VectorXdRefConst x)exotica::KinematicTree
UpdateFK()exotica::KinematicTreeprivate
UpdateH()exotica::KinematicTreeprivate
UpdateJ()exotica::KinematicTreeprivate
UpdateJointLimits()exotica::KinematicTreeprivate
UpdateModel()exotica::KinematicTree
UpdateTree()exotica::KinematicTreeprivate
velocity_limits_exotica::KinematicTreeprivate
~Uncopyable()=defaultexotica::Uncopyable


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