Tesseract
Motion Planning Environment
Loading...
Searching...
No Matches
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
32
34{
43{
44public:
45 // LCOV_EXCL_START
46 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
47 // LCOV_EXCL_STOP
48
49 using Ptr = std::shared_ptr<JointGroup>;
50 using ConstPtr = std::shared_ptr<const JointGroup>;
51 using UPtr = std::unique_ptr<JointGroup>;
52 using ConstUPtr = std::unique_ptr<const JointGroup>;
53
54 virtual ~JointGroup() = default;
55 JointGroup(const JointGroup& other);
56 JointGroup& operator=(const JointGroup& other);
57 JointGroup(JointGroup&&) = default;
59
67 JointGroup(std::string name,
68 std::vector<std::string> joint_names,
71
78 tesseract_common::TransformMap calcFwdKin(const Eigen::Ref<const Eigen::VectorXd>& joint_angles) const;
79
86 Eigen::MatrixXd calcJacobian(const Eigen::Ref<const Eigen::VectorXd>& joint_angles,
87 const std::string& link_name) const;
88
96 Eigen::MatrixXd calcJacobian(const Eigen::Ref<const Eigen::VectorXd>& joint_angles,
97 const std::string& link_name,
98 const Eigen::Vector3d& link_point) const;
99
106 Eigen::MatrixXd calcJacobian(const Eigen::Ref<const Eigen::VectorXd>& joint_angles,
107 const std::string& base_link_name,
108 const std::string& link_name) const;
109
118 Eigen::MatrixXd calcJacobian(const Eigen::Ref<const Eigen::VectorXd>& joint_angles,
119 const std::string& base_link_name,
120 const std::string& link_name,
121 const Eigen::Vector3d& link_point) const;
122
127 std::vector<std::string> getJointNames() const;
128
133 std::vector<std::string> getLinkNames() const;
134
142 std::vector<std::string> getActiveLinkNames() const;
143
149 std::vector<std::string> getStaticLinkNames() const;
150
156 bool isActiveLinkName(const std::string& link_name) const;
157
163 bool hasLinkName(const std::string& link_name) const;
164
170
176
181 std::vector<Eigen::Index> getRedundancyCapableJointIndices() const;
182
187 Eigen::Index numJoints() const;
188
190 std::string getBaseLinkName() const;
191
193 std::string getName() const;
194
200 bool checkJoints(const Eigen::Ref<const Eigen::VectorXd>& vec) const;
201
202protected:
203 std::string name_;
206 std::vector<std::string> joint_names_;
207 std::vector<std::string> link_names_;
208 std::vector<std::string> static_link_names_;
211 std::vector<Eigen::Index> redundancy_indices_;
212 std::vector<Eigen::Index> jacobian_map_;
213};
214
215} // namespace tesseract_kinematics
216
217#endif // TESSERACT_KINEMATICS_JOINT_GROUP_H
A Joint Group is defined by a list of joint_names.
Definition: joint_group.h:43
Eigen::Index numJoints() const
Number of joints in robot.
Definition: joint_group.cpp:288
tesseract_common::KinematicLimits getLimits() const
Get the kinematic limits (joint, velocity, acceleration, etc.)
Definition: joint_group.cpp:274
std::string name_
Definition: joint_group.h:203
std::string getBaseLinkName() const
Get the robot base link name.
Definition: joint_group.cpp:290
std::vector< Eigen::Index > getRedundancyCapableJointIndices() const
Get vector indicating which joints are capable of producing redundant solutions.
Definition: joint_group.cpp:286
tesseract_common::TransformMap calcFwdKin(const Eigen::Ref< const Eigen::VectorXd > &joint_angles) const
Calculates tool pose of robot chain.
Definition: joint_group.cpp:115
std::vector< std::string > static_link_names_
Definition: joint_group.h:208
std::shared_ptr< const JointGroup > ConstPtr
Definition: joint_group.h:50
tesseract_scene_graph::SceneState state_
Definition: joint_group.h:204
std::vector< std::string > getStaticLinkNames() const
Get list of static link names (with and without geometry) for kinematic object.
Definition: joint_group.cpp:262
bool hasLinkName(const std::string &link_name) const
Check if link name exists.
Definition: joint_group.cpp:269
JointGroup(JointGroup &&)=default
bool isActiveLinkName(const std::string &link_name) const
Check if link is an active link.
Definition: joint_group.cpp:264
std::vector< std::string > getJointNames() const
Get list of joint names for kinematic object.
Definition: joint_group.cpp:256
void setLimits(const tesseract_common::KinematicLimits &limits)
Setter for kinematic limits (joint, velocity, acceleration, etc.)
Definition: joint_group.cpp:276
tesseract_scene_graph::StateSolver::UPtr state_solver_
Definition: joint_group.h:205
std::vector< std::string > getActiveLinkNames() const
Get list of active link names (with and without geometry) for kinematic object.
Definition: joint_group.cpp:260
std::vector< Eigen::Index > redundancy_indices_
Definition: joint_group.h:211
tesseract_common::KinematicLimits limits_
Definition: joint_group.h:210
std::shared_ptr< JointGroup > Ptr
Definition: joint_group.h:49
std::vector< std::string > link_names_
Definition: joint_group.h:207
std::unique_ptr< const JointGroup > ConstUPtr
Definition: joint_group.h:52
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:122
std::vector< std::string > joint_names_
Definition: joint_group.h:206
JointGroup & operator=(const JointGroup &other)
Definition: joint_group.cpp:100
std::vector< Eigen::Index > jacobian_map_
Definition: joint_group.h:212
JointGroup & operator=(JointGroup &&)=default
tesseract_common::TransformMap static_link_transforms_
Definition: joint_group.h:209
std::string getName() const
Name of the manipulator.
Definition: joint_group.cpp:292
std::unique_ptr< JointGroup > UPtr
Definition: joint_group.h:51
std::vector< std::string > getLinkNames() const
Get list of all link names (with and without geometry) for kinematic object.
Definition: joint_group.cpp:258
bool checkJoints(const Eigen::Ref< const Eigen::VectorXd > &vec) const
Check for consistency in # and limits of joints.
Definition: joint_group.cpp:231
Definition: graph.h:125
std::unique_ptr< StateSolver > UPtr
Definition: state_solver.h:50
std::string base_link_name
Definition: ikfast_kinematics_7dof_unit.cpp:52
auto scene_graph
Definition: ikfast_kinematics_7dof_unit.cpp:51
Tesseract Scene Graph State Solver KDL Implementation.
tesseract_scene_graph::SceneState scene_state
Definition: kinematics_factory_unit.cpp:265
AlignedMap< std::string, Eigen::Isometry3d > TransformMap
Definition: types.h:66
Definition: forward_kinematics.h:44
This holds a state of the scene.
Store kinematic limits.
Definition: kinematic_limits.h:39
This holds a state of the scene.
Definition: scene_state.h:54
Common Tesseract Types.
joint_state joint_names
Definition: tesseract_common_serialization_unit.cpp:75
joint_1 limits
Definition: tesseract_scene_graph_joint_unit.cpp:153