115 std::cout <<
"Loading robot: " << robot_name <<
" for planning group: " << group_name <<
'\n';
133 for (std::size_t i = 0; i <
num_dofs_; ++i)
unsigned int getVariableCount() const
Get the number of variables that describe this joint group. This includes variables necessary for mim...
const std::vector< std::string > & getLinkModelNames() const
Get the names of the links that are part of this joint group.
Robot independent test class setup.
moveit::core::RobotStatePtr robot_state_
Eigen::VectorXd getDeterministicState() const
Create a joint position vector with values 0.1, 0.2, 0.3, ... where the length depends on the number ...
moveit::core::RobotModelPtr robot_model_
std::string ee_link_name_
LoadTestRobot(const std::string &robot_name, const std::string &group_name)
const moveit::core::JointModelGroup * joint_model_group_
Eigen::VectorXd getRandomState() const
std::string base_link_name_
moveit::core::RobotModelPtr loadTestingRobotModel(const std::string &package_name, const std::string &urdf_relative_path, const std::string &srdf_relative_path)
Loads a robot model given a URDF and SRDF file in a package.