1 #include <gtest/gtest.h> 61 std::vector<std::string> link_names;
62 const std::vector<double> joint_angles = { 0, 0.1, 0.2, 0.3, 0.4, 0.5 };
63 std::vector<geometry_msgs::Pose> poses_out;
69 const std::vector<geometry_msgs::Pose> poses_in = { poses_out[0] };
70 std::vector<std::vector<double> > solutions;
76 Eigen::Affine3d actual, desired;
78 for (
auto js : solutions)
86 int main(
int argc,
char** argv)
88 ros::init(argc, argv,
"moveit_opw_kinematics_test_fanuc");
89 testing::InitGoogleTest(&argc, argv);
90 return RUN_ALL_TESTS();
int main(int argc, char **argv)
virtual const std::string & getGroupName() const
const std::string ROOT_LINK_PARAM
virtual bool getPositionFK(const std::vector< std::string > &link_names, const std::vector< double > &joint_angles, std::vector< geometry_msgs::Pose > &poses) const override
const std::vector< std::string > & getLinkNames() const override
Return all the link names in the order they are represented internally.
void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
const std::string GROUP_PARAM
virtual bool getPositionIK(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, std::vector< double > &solution, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const override
virtual bool initialize(const std::string &robot_description, const std::string &group_name, const std::string &base_name, const std::string &tip_frame, double search_discretization) override
Specific implementation of kinematics using ROS service calls to communicate with external IK solvers...
void comparePoses(const Transform< T > &Ta, const Transform< T > &Tb)
Compare every element of two eigen affine3 poses.
const std::string ROBOT_DESCRIPTION
std::string robot_description_name_
moveit_opw_kinematics_plugin::MoveItOPWKinematicsPlugin plugin_
bool getParam(const std::string &key, std::string &s) const
#define ROS_ERROR_STREAM(args)
#define EXPECT_TRUE(args)
TEST_F(TestPlugin, InitOk)
const std::string TIP_LINK_PARAM