#include <kinematic_element.h>
Public Member Functions | |
KDL::Frame | GetPose (const double &x=0.0) |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW | KinematicElement (int _id, std::shared_ptr< KinematicElement > _parent, const KDL::Segment &_segment) |
void | RemoveExpiredChildren () |
void | UpdateClosestRobotLink () |
~KinematicElement () | |
Public Attributes | |
double | acceleration_limit = std::numeric_limits<double>::quiet_NaN() |
std::vector< std::weak_ptr< KinematicElement > > | children |
std::weak_ptr< KinematicElement > | closest_robot_link = std::shared_ptr<KinematicElement>(nullptr) |
Eigen::Vector4d | color = Eigen::Vector4d(0.5, 0.5, 0.5, 1.0) |
int | control_id = -1 |
KDL::Frame | frame = KDL::Frame::Identity() |
KDL::Frame | generated_offset = KDL::Frame::Identity() |
int | id |
bool | is_controlled = false |
bool | is_robot_link = false |
bool | is_trajectory_generated = false |
std::vector< double > | joint_limits |
std::weak_ptr< KinematicElement > | parent |
std::string | parent_name |
Eigen::Vector3d | scale = Eigen::Vector3d::Ones() |
KDL::Segment | segment = KDL::Segment() |
shapes::ShapeConstPtr | shape = nullptr |
std::string | shape_resource_path = std::string() |
double | velocity_limit = std::numeric_limits<double>::quiet_NaN() |
std::vector< VisualElement > | visual |
Private Member Functions | |
void | SetChildrenClosestRobotLink () |
Definition at line 54 of file kinematic_element.h.
|
inline |
Definition at line 59 of file kinematic_element.h.
|
inline |
Definition at line 63 of file kinematic_element.h.
|
inline |
Definition at line 89 of file kinematic_element.h.
|
inline |
Definition at line 101 of file kinematic_element.h.
|
inlineprivate |
Definition at line 134 of file kinematic_element.h.
|
inline |
Definition at line 73 of file kinematic_element.h.
double exotica::KinematicElement::acceleration_limit = std::numeric_limits<double>::quiet_NaN() |
Definition at line 125 of file kinematic_element.h.
std::vector<std::weak_ptr<KinematicElement> > exotica::KinematicElement::children |
Definition at line 117 of file kinematic_element.h.
std::weak_ptr<KinematicElement> exotica::KinematicElement::closest_robot_link = std::shared_ptr<KinematicElement>(nullptr) |
Definition at line 118 of file kinematic_element.h.
Eigen::Vector4d exotica::KinematicElement::color = Eigen::Vector4d(0.5, 0.5, 0.5, 1.0) |
Definition at line 130 of file kinematic_element.h.
int exotica::KinematicElement::control_id = -1 |
Definition at line 113 of file kinematic_element.h.
KDL::Frame exotica::KinematicElement::frame = KDL::Frame::Identity() |
Definition at line 120 of file kinematic_element.h.
KDL::Frame exotica::KinematicElement::generated_offset = KDL::Frame::Identity() |
Definition at line 121 of file kinematic_element.h.
int exotica::KinematicElement::id |
Definition at line 112 of file kinematic_element.h.
bool exotica::KinematicElement::is_controlled = false |
Definition at line 114 of file kinematic_element.h.
bool exotica::KinematicElement::is_robot_link = false |
Definition at line 129 of file kinematic_element.h.
bool exotica::KinematicElement::is_trajectory_generated = false |
Definition at line 122 of file kinematic_element.h.
std::vector<double> exotica::KinematicElement::joint_limits |
Definition at line 123 of file kinematic_element.h.
std::weak_ptr<KinematicElement> exotica::KinematicElement::parent |
Definition at line 115 of file kinematic_element.h.
std::string exotica::KinematicElement::parent_name |
Definition at line 116 of file kinematic_element.h.
Eigen::Vector3d exotica::KinematicElement::scale = Eigen::Vector3d::Ones() |
Definition at line 128 of file kinematic_element.h.
KDL::Segment exotica::KinematicElement::segment = KDL::Segment() |
Definition at line 119 of file kinematic_element.h.
shapes::ShapeConstPtr exotica::KinematicElement::shape = nullptr |
Definition at line 126 of file kinematic_element.h.
std::string exotica::KinematicElement::shape_resource_path = std::string() |
Definition at line 127 of file kinematic_element.h.
double exotica::KinematicElement::velocity_limit = std::numeric_limits<double>::quiet_NaN() |
Definition at line 124 of file kinematic_element.h.
std::vector<VisualElement> exotica::KinematicElement::visual |
Definition at line 131 of file kinematic_element.h.