53 robot_model_ = builder.
build();
54 robot_state_ = std::make_shared<RobotState>(robot_model_);
68 std::cout <<
"Testing simple planar robot jacobian\n";
71 auto joint_model_group = robot_model_->getJointModelGroup(
"group");
73 std::vector<double> q_test{ 0.0, 0.0, 0.0 };
75 robot_state_->setJointGroupPositions(joint_model_group, q_test);
76 robot_state_->updateLinkTransforms();
79 Eigen::MatrixXd jacobian;
80 robot_state_->getJacobian(joint_model_group, robot_state_->getLinkModel(
"b"), reference_point_position, jacobian);
85 robot_state_->setJointGroupPositions(joint_model_group, q_test);
86 robot_state_->updateLinkTransforms();
89 Eigen::MatrixXd jacobian_2;
90 robot_state_->getJacobian(joint_model_group, robot_state_->getLinkModel(
"b"), reference_point_position, jacobian_2);
92 std::cout <<
"First Jacobian = \n" << jacobian <<
"\n";
93 std::cout <<
"Second Jacobian = \n" << jacobian_2 <<
"\n";
98 int main(
int argc,
char** argv)
100 testing::InitGoogleTest(&argc, argv);
101 return RUN_ALL_TESTS();