Contains information about a planning group. More...
#include <chomp_robot_model.h>
Public Member Functions | |
bool | addCollisionPoint (ChompCollisionPoint &collision_point, ChompRobotModel &robot_model) |
template<typename Derived > | |
void | getRandomState (Eigen::MatrixBase< Derived > &state_vec) const |
Public Attributes | |
std::vector< ChompJoint > | chomp_joints_ |
std::vector< std::string > | collision_link_names_ |
std::vector< ChompCollisionPoint > | collision_points_ |
boost::shared_ptr < KDL::TreeFkSolverJointPosAxisPartial > | fk_solver_ |
std::vector< std::string > | link_names_ |
std::string | name_ |
int | num_joints_ |
Contains information about a planning group.
Definition at line 71 of file chomp_robot_model.h.
bool chomp::ChompRobotModel::ChompPlanningGroup::addCollisionPoint | ( | ChompCollisionPoint & | collision_point, | |
ChompRobotModel & | robot_model | |||
) |
Adds the collision point to this planning group, if any of the joints in this group can control the collision point in some way. Also converts the ChompCollisionPoint::parent_joints vector into group joint indexes
Definition at line 327 of file chomp_robot_model.cpp.
void chomp::ChompRobotModel::ChompPlanningGroup::getRandomState | ( | Eigen::MatrixBase< Derived > & | state_vec | ) | const [inline] |
Gets a random state vector within the joint limits
Definition at line 278 of file chomp_robot_model.h.
Joints used in planning
Definition at line 75 of file chomp_robot_model.h.
std::vector<std::string> chomp::ChompRobotModel::ChompPlanningGroup::collision_link_names_ |
Links used in collision checking
Definition at line 77 of file chomp_robot_model.h.
Ordered list of collision checking points (from root to tip)
Definition at line 78 of file chomp_robot_model.h.
boost::shared_ptr<KDL::TreeFkSolverJointPosAxisPartial> chomp::ChompRobotModel::ChompPlanningGroup::fk_solver_ |
Forward kinematics solver for the group
Definition at line 79 of file chomp_robot_model.h.
std::vector<std::string> chomp::ChompRobotModel::ChompPlanningGroup::link_names_ |
Links used in planning
Definition at line 76 of file chomp_robot_model.h.
Name of the planning group
Definition at line 73 of file chomp_robot_model.h.
Number of joints used in planning
Definition at line 74 of file chomp_robot_model.h.