Go to the documentation of this file.
26 #ifndef TESSERACT_KINEMATICS_JOINT_GROUP_H
27 #define TESSERACT_KINEMATICS_JOINT_GROUP_H
48 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
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>;
70 std::vector<std::string> joint_names,
88 Eigen::MatrixXd
calcJacobian(
const Eigen::Ref<const Eigen::VectorXd>& joint_angles,
89 const std::string& link_name)
const;
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;
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;
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;
165 bool hasLinkName(
const std::string& link_name)
const;
202 bool checkJoints(
const Eigen::Ref<const Eigen::VectorXd>& vec)
const;
219 #endif // TESSERACT_KINEMATICS_JOINT_GROUP_H
Eigen::MatrixXd calcJacobian(const Eigen::Ref< const Eigen::VectorXd > &joint_angles, const std::string &link_name) const
Calculated jacobian of robot given joint angles.
bool isActiveLinkName(const std::string &link_name) const
Check if link is an active link.
Eigen::Index numJoints() const
Number of joints in robot.
std::vector< std::string > getStaticLinkNames() const
Get list of static link names (with and without geometry) for kinematic object.
bool hasLinkName(const std::string &link_name) const
Check if link name exists.
AlignedMap< std::string, Eigen::Isometry3d > TransformMap
A Joint Group is defined by a list of joint_names.
std::string getBaseLinkName() const
Get the robot base link name.
std::vector< Eigen::Index > jacobian_map_
std::unique_ptr< JointGroup > UPtr
tesseract_scene_graph::SceneState state_
std::vector< std::string > static_link_names_
tesseract_common::KinematicLimits limits_
std::string getName() const
Name of the manipulator.
JointGroup & operator=(const JointGroup &other)
std::vector< std::string > getLinkNames() const
Get list of all link names (with and without geometry) for kinematic object.
tesseract_common::TransformMap static_link_transforms_
std::vector< std::string > getJointNames() const
Get list of joint names for kinematic object.
std::unique_ptr< tesseract_scene_graph::StateSolver > state_solver_
std::vector< std::string > link_names_
std::unique_ptr< const JointGroup > ConstUPtr
std::vector< std::string > getActiveLinkNames() const
Get list of active link names (with and without geometry) for kinematic object.
JointGroup(const JointGroup &other)
std::shared_ptr< JointGroup > Ptr
std::vector< Eigen::Index > getRedundancyCapableJointIndices() const
Get vector indicating which joints are capable of producing redundant solutions.
bool checkJoints(const Eigen::Ref< const Eigen::VectorXd > &vec) const
Check for consistency in # and limits of joints.
std::shared_ptr< const JointGroup > ConstPtr
tesseract_common::KinematicLimits getLimits() const
Get the kinematic limits (joint, velocity, acceleration, etc.)
tesseract_common::TransformMap calcFwdKin(const Eigen::Ref< const Eigen::VectorXd > &joint_angles) const
Calculates tool pose of robot chain.
std::vector< std::string > joint_names_
std::vector< Eigen::Index > redundancy_indices_
void setLimits(const tesseract_common::KinematicLimits &limits)
Setter for kinematic limits (joint, velocity, acceleration, etc.)