joint_group.h
Go to the documentation of this file.
1 
26 #ifndef TESSERACT_KINEMATICS_JOINT_GROUP_H
27 #define TESSERACT_KINEMATICS_JOINT_GROUP_H
28 
34 
35 namespace tesseract_kinematics
36 {
45 {
46 public:
47  // LCOV_EXCL_START
48  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
49  // LCOV_EXCL_STOP
50 
51  using Ptr = std::shared_ptr<JointGroup>;
52  using ConstPtr = std::shared_ptr<const JointGroup>;
53  using UPtr = std::unique_ptr<JointGroup>;
54  using ConstUPtr = std::unique_ptr<const JointGroup>;
55 
56  virtual ~JointGroup();
57  JointGroup(const JointGroup& other);
58  JointGroup& operator=(const JointGroup& other);
59  JointGroup(JointGroup&&) = default;
60  JointGroup& operator=(JointGroup&&) = default;
61 
69  JointGroup(std::string name,
70  std::vector<std::string> joint_names,
71  const tesseract_scene_graph::SceneGraph& scene_graph,
72  const tesseract_scene_graph::SceneState& scene_state);
73 
80  tesseract_common::TransformMap calcFwdKin(const Eigen::Ref<const Eigen::VectorXd>& joint_angles) const;
81 
88  Eigen::MatrixXd calcJacobian(const Eigen::Ref<const Eigen::VectorXd>& joint_angles,
89  const std::string& link_name) const;
90 
98  Eigen::MatrixXd calcJacobian(const Eigen::Ref<const Eigen::VectorXd>& joint_angles,
99  const std::string& link_name,
100  const Eigen::Vector3d& link_point) const;
101 
108  Eigen::MatrixXd calcJacobian(const Eigen::Ref<const Eigen::VectorXd>& joint_angles,
109  const std::string& base_link_name,
110  const std::string& link_name) const;
111 
120  Eigen::MatrixXd calcJacobian(const Eigen::Ref<const Eigen::VectorXd>& joint_angles,
121  const std::string& base_link_name,
122  const std::string& link_name,
123  const Eigen::Vector3d& link_point) const;
124 
129  std::vector<std::string> getJointNames() const;
130 
135  std::vector<std::string> getLinkNames() const;
136 
144  std::vector<std::string> getActiveLinkNames() const;
145 
151  std::vector<std::string> getStaticLinkNames() const;
152 
158  bool isActiveLinkName(const std::string& link_name) const;
159 
165  bool hasLinkName(const std::string& link_name) const;
166 
172 
177  void setLimits(const tesseract_common::KinematicLimits& limits);
178 
183  std::vector<Eigen::Index> getRedundancyCapableJointIndices() const;
184 
189  Eigen::Index numJoints() const;
190 
192  std::string getBaseLinkName() const;
193 
195  std::string getName() const;
196 
202  bool checkJoints(const Eigen::Ref<const Eigen::VectorXd>& vec) const;
203 
204 protected:
205  std::string name_;
207  std::unique_ptr<tesseract_scene_graph::StateSolver> state_solver_;
208  std::vector<std::string> joint_names_;
209  std::vector<std::string> link_names_;
210  std::vector<std::string> static_link_names_;
213  std::vector<Eigen::Index> redundancy_indices_;
214  std::vector<Eigen::Index> jacobian_map_;
215 };
216 
217 } // namespace tesseract_kinematics
218 
219 #endif // TESSERACT_KINEMATICS_JOINT_GROUP_H
tesseract_kinematics::JointGroup::calcJacobian
Eigen::MatrixXd calcJacobian(const Eigen::Ref< const Eigen::VectorXd > &joint_angles, const std::string &link_name) const
Calculated jacobian of robot given joint angles.
Definition: joint_group.cpp:133
tesseract_kinematics::JointGroup::isActiveLinkName
bool isActiveLinkName(const std::string &link_name) const
Check if link is an active link.
Definition: joint_group.cpp:275
tesseract_kinematics::JointGroup::numJoints
Eigen::Index numJoints() const
Number of joints in robot.
Definition: joint_group.cpp:299
tesseract_kinematics::JointGroup::getStaticLinkNames
std::vector< std::string > getStaticLinkNames() const
Get list of static link names (with and without geometry) for kinematic object.
Definition: joint_group.cpp:273
tesseract_common::KinematicLimits
tesseract_kinematics::JointGroup::hasLinkName
bool hasLinkName(const std::string &link_name) const
Check if link name exists.
Definition: joint_group.cpp:280
tesseract_common::TransformMap
AlignedMap< std::string, Eigen::Isometry3d > TransformMap
tesseract_kinematics::JointGroup
A Joint Group is defined by a list of joint_names.
Definition: joint_group.h:44
tesseract_kinematics::JointGroup::getBaseLinkName
std::string getBaseLinkName() const
Get the robot base link name.
Definition: joint_group.cpp:301
tesseract_kinematics::JointGroup::jacobian_map_
std::vector< Eigen::Index > jacobian_map_
Definition: joint_group.h:214
kinematic_limits.h
tesseract_kinematics::JointGroup::UPtr
std::unique_ptr< JointGroup > UPtr
Definition: joint_group.h:53
tesseract_kinematics::JointGroup::state_
tesseract_scene_graph::SceneState state_
Definition: joint_group.h:206
tesseract_scene_graph::SceneGraph
tesseract_kinematics::JointGroup::static_link_names_
std::vector< std::string > static_link_names_
Definition: joint_group.h:210
tesseract_kinematics::JointGroup::limits_
tesseract_common::KinematicLimits limits_
Definition: joint_group.h:212
tesseract_kinematics::JointGroup::name_
std::string name_
Definition: joint_group.h:205
tesseract_scene_graph::SceneState
tesseract_kinematics::JointGroup::getName
std::string getName() const
Name of the manipulator.
Definition: joint_group.cpp:303
tesseract_kinematics::JointGroup::operator=
JointGroup & operator=(const JointGroup &other)
Definition: joint_group.cpp:111
tesseract_kinematics::JointGroup::getLinkNames
std::vector< std::string > getLinkNames() const
Get list of all link names (with and without geometry) for kinematic object.
Definition: joint_group.cpp:269
tesseract_kinematics::JointGroup::static_link_transforms_
tesseract_common::TransformMap static_link_transforms_
Definition: joint_group.h:211
tesseract_kinematics::JointGroup::getJointNames
std::vector< std::string > getJointNames() const
Get list of joint names for kinematic object.
Definition: joint_group.cpp:267
tesseract_kinematics::JointGroup::state_solver_
std::unique_ptr< tesseract_scene_graph::StateSolver > state_solver_
Definition: joint_group.h:207
tesseract_kinematics::JointGroup::link_names_
std::vector< std::string > link_names_
Definition: joint_group.h:209
tesseract_kinematics::JointGroup::ConstUPtr
std::unique_ptr< const JointGroup > ConstUPtr
Definition: joint_group.h:54
tesseract_kinematics::JointGroup::getActiveLinkNames
std::vector< std::string > getActiveLinkNames() const
Get list of active link names (with and without geometry) for kinematic object.
Definition: joint_group.cpp:271
tesseract_kinematics::JointGroup::JointGroup
JointGroup(const JointGroup &other)
Definition: joint_group.cpp:109
tesseract_kinematics::JointGroup::Ptr
std::shared_ptr< JointGroup > Ptr
Definition: joint_group.h:51
fwd.h
tesseract_kinematics::JointGroup::getRedundancyCapableJointIndices
std::vector< Eigen::Index > getRedundancyCapableJointIndices() const
Get vector indicating which joints are capable of producing redundant solutions.
Definition: joint_group.cpp:297
eigen_types.h
scene_state.h
tesseract_kinematics::JointGroup::checkJoints
bool checkJoints(const Eigen::Ref< const Eigen::VectorXd > &vec) const
Check for consistency in # and limits of joints.
Definition: joint_group.cpp:242
tesseract_kinematics::JointGroup::ConstPtr
std::shared_ptr< const JointGroup > ConstPtr
Definition: joint_group.h:52
tesseract_kinematics::JointGroup::getLimits
tesseract_common::KinematicLimits getLimits() const
Get the kinematic limits (joint, velocity, acceleration, etc.)
Definition: joint_group.cpp:285
tesseract_kinematics
Definition: forward_kinematics.h:40
tesseract_kinematics::JointGroup::calcFwdKin
tesseract_common::TransformMap calcFwdKin(const Eigen::Ref< const Eigen::VectorXd > &joint_angles) const
Calculates tool pose of robot chain.
Definition: joint_group.cpp:126
tesseract_kinematics::JointGroup::joint_names_
std::vector< std::string > joint_names_
Definition: joint_group.h:208
tesseract_kinematics::JointGroup::~JointGroup
virtual ~JointGroup()
tesseract_kinematics::JointGroup::redundancy_indices_
std::vector< Eigen::Index > redundancy_indices_
Definition: joint_group.h:213
tesseract_kinematics::JointGroup::setLimits
void setLimits(const tesseract_common::KinematicLimits &limits)
Setter for kinematic limits (joint, velocity, acceleration, etc.)
Definition: joint_group.cpp:287


tesseract_kinematics
Author(s): Levi Armstrong
autogenerated on Sun May 18 2025 03:02:14