Go to the documentation of this file.
30 #ifndef EXOTICA_CORE_KINEMATIC_TREE_H_
31 #define EXOTICA_CORE_KINEMATIC_TREE_H_
40 #include <visualization_msgs/MarkerArray.h>
41 #include <Eigen/Eigen>
42 #include <kdl/jacobian.hpp>
43 #include <kdl/tree.hpp>
70 constexpr
double inf = 1e20;
86 KinematicFrameRequest(std::string _frame_A_link_name, KDL::Frame _frame_A_offset = KDL::Frame(), std::string _frame_B_link_name =
"", KDL::Frame _frame_B_offset = KDL::Frame());
97 std::vector<KinematicFrameRequest>
frames;
132 void Create(std::shared_ptr<KinematicResponse> solution);
135 Eigen::Map<Eigen::VectorXd>
X{
nullptr, 0};
136 Eigen::Map<ArrayFrame>
Phi{
nullptr, 0};
145 void Instantiate(
const std::string& joint_group, robot_model::RobotModelPtr model,
const std::string&
name);
160 void SetFloatingBaseLimitsPosXYZEulerZYX(
const std::vector<double>& lower,
const std::vector<double>& upper,
const std::vector<double>& velocity,
const std::vector<double>& acceleration);
162 void SetPlanarBaseLimitsPosXYEulerZ(
const std::vector<double>& lower,
const std::vector<double>& upper,
const std::vector<double>& velocity,
const std::vector<double>& acceleration);
169 void PublishFrames(
const std::string& tf_prefix =
"exotica");
196 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;
197 KDL::Frame
FK(
const std::string& element_A,
const KDL::Frame& offset_a,
const std::string& element_B,
const KDL::Frame& offset_b)
const;
198 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;
199 Eigen::MatrixXd
Jacobian(
const std::string& element_A,
const KDL::Frame& offset_a,
const std::string& element_B,
const KDL::Frame& offset_b)
const;
200 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;
201 exotica::Hessian Hessian(
const std::string& element_A,
const KDL::Frame& offset_a,
const std::string& element_B,
const KDL::Frame& offset_b)
const;
204 std::shared_ptr<KinematicElement>
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);
205 std::shared_ptr<KinematicElement>
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);
206 std::shared_ptr<KinematicElement>
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);
208 void ChangeParent(
const std::string& name,
const std::string& parent,
const KDL::Frame& pose,
bool relative);
209 int IsControlled(std::shared_ptr<KinematicElement> joint);
219 std::vector<std::string>
GetKinematicChain(
const std::string& begin,
const std::string& end)
const;
231 const std::vector<std::weak_ptr<KinematicElement>>&
GetTree()
const {
return tree_; }
254 void BuildTree(
const KDL::Tree& RobotKinematics);
284 std::vector<std::weak_ptr<KinematicElement>>
tree_;
287 std::map<std::string, std::weak_ptr<KinematicElement>>
tree_map_;
289 std::shared_ptr<KinematicElement>
root_;
297 std::shared_ptr<KinematicResponse>
solution_ = std::make_shared<KinematicResponse>();
310 #endif // EXOTICA_CORE_KINEMATIC_TREE_H_
std::shared_ptr< KinematicResponse > RequestFrames(const KinematicsRequest &request)
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
std::vector< KinematicFrameRequest > frames
void Update(Eigen::VectorXdRefConst x)
Eigen::Map< ArrayFrame > Phi
int num_controlled_joints_
Number of controlled joints in the joint group.
const std::string & GetRootFrameName() const
visualization_msgs::MarkerArray marker_array_msg_
bool DoesLinkWithNameExist(std::string name) const
Checks whether a link with this name exists in any of the trees.
int IsControlledLink(const std::string &link_name)
std::shared_ptr< KinematicResponse > GetKinematicResponse()
std::vector< std::string > model_link_names_
KinematicRequestFlags flags
Eigen::VectorXd acceleration_limits_
void SetJointAccelerationLimits(Eigen::VectorXdRefConst acceleration_in)
const std::map< std::string, std::weak_ptr< KinematicElement > > & GetModelJointsMap() 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
const Eigen::MatrixXd & GetJointLimits() const
std::vector< std::string > model_joints_names_
std::vector< std::shared_ptr< KinematicElement > > model_tree_
std::string frame_A_link_name
void ChangeParent(const std::string &name, const std::string &parent, const KDL::Frame &pose, bool relative)
int GetNumControlledJoints() const
KDL::Frame frame_B_offset
std::map< std::string, std::weak_ptr< KinematicElement > > controlled_joints_map_
const std::map< std::string, std::weak_ptr< KinematicElement > > & GetTreeMap() const
bool HasModelLink(const std::string &link) const
void SetKinematicResponse(std::shared_ptr< KinematicResponse > response_in)
bool debug_scene_changed_
std::shared_ptr< KinematicResponse > solution_
Eigen::Map< ArrayTwist > Phi_dot
std::vector< std::string > GetKinematicChain(const std::string &begin, const std::string &end) const
GetKinematicChain get list of joints in a kinematic chain.
Eigen::Array< Eigen::MatrixXd, Eigen::Dynamic, 1 > Hessian
const std::map< std::string, std::weak_ptr< KinematicElement > > & GetControlledJointsMap() const
const std::vector< std::string > & GetModelJointNames() const
const std::map< std::string, std::weak_ptr< KinematicElement > > & GetCollisionTreeMap() const
std::map< std::string, std::weak_ptr< KinematicElement > > model_joints_map_
KDL::Frame frame_B_offset
const std::vector< std::string > & GetModelLinkNames() const
void BuildTree(const KDL::Tree &RobotKinematics)
robot_model::RobotModelPtr GetRobotModel() const
const std::string & GetRootJointName() const
KinematicRequestFlags flags
int num_joints_
Number of joints of the model (including floating/planar base, passive joints, and uncontrolled joint...
void ComputeH(KinematicFrame &frame, const KDL::Jacobian &jacobian, exotica::Hessian &hessian) const
BaseType model_base_type_
void SetJointLimitsLower(Eigen::VectorXdRefConst lower_in)
Eigen::Map< ArrayJacobian > jacobian
const typedef Eigen::Ref< const Eigen::VectorXd > & VectorXdRefConst
Convenience wrapper for storing references to sub-matrices/vectors.
std::vector< tf::StampedTransform > debug_frames_
std::vector< tf::StampedTransform > debug_tree_
std::shared_ptr< KinematicElement > 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)
Eigen::Array< Eigen::Array< Eigen::MatrixXd, Eigen::Dynamic, 1 >, Eigen::Dynamic, 1 > ArrayHessian
std::vector< std::weak_ptr< KinematicElement > > controlled_joints_
std::vector< std::shared_ptr< KinematicElement > > environment_tree_
void ComputeJ(KinematicFrame &frame, KDL::Jacobian &jacobian) const
Eigen::VectorXd GetRandomControlledState()
Random state generation.
Eigen::VectorXd GetControlledState() const
int IsControlled(std::shared_ptr< KinematicElement > joint)
KinematicRequestFlags flags_
const Eigen::VectorXd & GetAccelerationLimits() const
const std::vector< std::string > & GetControlledLinkNames() const
Eigen::Map< ArrayHessian > hessian
std::map< std::string, std::weak_ptr< KinematicElement > > tree_map_
Eigen::VectorXd GetModelState() const
std::string root_joint_name_
void AddElementFromSegmentMapIterator(KDL::SegmentMap::const_iterator segment, std::shared_ptr< KinematicElement > parent)
std::vector< std::string > controlled_joints_names_
KDL::Frame frame_A_offset
std::weak_ptr< KinematicElement > frame_A
std::shared_ptr< KinematicElement > FindKinematicElementByName(const std::string &frame_name)
BaseType GetModelBaseType() const
std::map< std::string, double > GetModelStateMap() const
const std::vector< std::string > & GetControlledJointNames() const
const std::vector< std::shared_ptr< KinematicElement > > & GetModelTree() const
const Eigen::VectorXd & GetVelocityLimits() const
void SetJointVelocityLimits(Eigen::VectorXdRefConst velocity_in)
std::weak_ptr< KinematicElement > frame_B
std::map< std::string, std::weak_ptr< KinematicElement > > collision_tree_map_
const bool & HasAccelerationLimits() const
BaseType GetControlledBaseType() const
void SetFloatingBaseLimitsPosXYZEulerZYX(const std::vector< double > &lower, const std::vector< double > &upper)
void Create(std::shared_ptr< KinematicResponse > solution)
std::vector< std::string > controlled_link_names_
BaseType controlled_base_type_
The KinematicResponse is the container to keep kinematic update data. The corresponding KinematicSolu...
std::shared_ptr< KinematicElement > 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)
KDL::Frame frame_A_offset
Eigen::Array< KDL::Jacobian, Eigen::Dynamic, 1 > ArrayJacobian
Eigen::Map< Eigen::VectorXd > X
ros::Publisher shapes_pub_
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.
Eigen::VectorXd velocity_limits_
const std::vector< std::weak_ptr< KinematicElement > > & GetTree() const
KinematicRequestFlags operator|(KinematicRequestFlags a, KinematicRequestFlags b)
std::shared_ptr< const Shape > ShapeConstPtr
void SetSeed(const uint_fast32_t seed)
SetSeed sets the seed of the random generator for deterministic joint state sampling.
KinematicRequestFlags operator&(KinematicRequestFlags a, KinematicRequestFlags b)
void SetPlanarBaseLimitsPosXYEulerZ(const std::vector< double > &lower, const std::vector< double > &upper)
ros::Publisher octomap_pub_
std::map< std::string, shapes::ShapeType > GetCollisionObjectTypes() const
std::vector< KinematicFrame > frame
Eigen::Array< KDL::Twist, Eigen::Dynamic, 1 > ArrayTwist
void SetModelState(Eigen::VectorXdRefConst x)
Eigen::VectorXd tree_state_
bool has_acceleration_limit_
std::vector< std::uniform_real_distribution< double > > random_state_distributions_
int GetNumModelJoints() const
void Instantiate(const std::string &joint_group, robot_model::RobotModelPtr model, const std::string &name)
void PublishFrames(const std::string &tf_prefix="exotica")
const std::vector< std::weak_ptr< KinematicElement > > & GetControlledJoints() const
KDL::Frame FK(KinematicFrame &frame) const
void SetJointLimitsUpper(Eigen::VectorXdRefConst upper_in)
Eigen::VectorXd GetControlledLinkMass() const
std::vector< std::weak_ptr< KinematicElement > > tree_
std::shared_ptr< KinematicElement > root_
std::string frame_B_link_name
std::map< std::string, std::vector< double > > GetUsedJointLimits() const
robot_model::RobotModelPtr model_
Eigen::Array< KDL::Frame, Eigen::Dynamic, 1 > ArrayFrame
The KinematicSolution is created from - and maps into - a KinematicResponse.
Eigen::MatrixXd joint_limits_
exotica_core
Author(s): Yiming Yang, Michael Camilleri
autogenerated on Fri Aug 2 2024 08:43:02