39 #include <eigen_stl_containers/eigen_stl_containers.h>
41 #include <gtest/gtest.h>
46 const char*
const msg_;
47 double*
const gold_standard_;
48 const std::chrono::time_point<std::chrono::steady_clock> start_;
52 ScopedTimer(
const char* msg =
"",
double* gold_standard =
nullptr)
53 : msg_(msg), gold_standard_(gold_standard), start_(std::chrono::steady_clock::now())
59 std::chrono::duration<double> elapsed = std::chrono::steady_clock::now() - start_;
60 std::cerr << msg_ << elapsed.count() * 1000. <<
"ms ";
64 if (*gold_standard_ == 0)
65 *gold_standard_ = elapsed.count();
66 std::cerr << 100 * elapsed.count() / *gold_standard_ <<
"%";
77 Eigen::Isometry3d iso = Eigen::Translation3d(1, 2, 3) * Eigen::AngleAxisd(0.13 * M_PI, Eigen::Vector3d::UnitX()) *
78 Eigen::AngleAxisd(0.29 * M_PI, Eigen::Vector3d::UnitY()) *
79 Eigen::AngleAxisd(0.42 * M_PI, Eigen::Vector3d::UnitZ());
80 transforms_.push_back(Eigen::Isometry3d::Identity());
89 const Eigen::Isometry3d
id = Eigen::Isometry3d::Identity();
99 ASSERT_TRUE(
bool(model));
102 for (
unsigned i = 0; i < 1e5; ++i)
112 double gold_standard = 0;
114 ScopedTimer t(
"Eigen::Affine * Eigen::Matrix: ", &gold_standard);
115 for (
size_t i = 0; i < runs; ++i)
116 transforms_[result_idx_].affine().noalias() = transforms_[input_idx_].affine() * transforms_[input_idx_].matrix();
119 ScopedTimer t(
"Eigen::Matrix * Eigen::Matrix: ", &gold_standard);
120 for (
size_t i = 0; i < runs; ++i)
121 transforms_[result_idx_].matrix().noalias() = transforms_[input_idx_].matrix() * transforms_[input_idx_].matrix();
124 ScopedTimer t(
"Eigen::Isometry * Eigen::Isometry: ", &gold_standard);
125 for (
size_t i = 0; i < runs; ++i)
126 transforms_[result_idx_] = transforms_[input_idx_] * transforms_[input_idx_];
132 EigenSTL::vector_Affine3d affine(1);
133 affine[0].matrix() = transforms_[input_idx_].matrix();
135 double gold_standard = 0;
137 ScopedTimer t(
"Isometry3d::inverse(): ", &gold_standard);
138 for (
size_t i = 0; i < runs; ++i)
139 transforms_[result_idx_] = transforms_[input_idx_].inverse();
141 volatile size_t input_idx = 0;
143 ScopedTimer t(
"Affine3d::inverse(Eigen::Isometry): ", &gold_standard);
144 for (
size_t i = 0; i < runs; ++i)
145 transforms_[result_idx_].affine().noalias() = affine[input_idx].inverse(Eigen::Isometry).affine();
148 ScopedTimer t(
"Affine3d::inverse(): ", &gold_standard);
149 for (
size_t i = 0; i < runs; ++i)
150 transforms_[result_idx_].affine().noalias() = affine[input_idx].inverse().affine();
153 ScopedTimer t(
"Matrix4d::inverse(): ", &gold_standard);
154 for (
size_t i = 0; i < runs; ++i)
155 transforms_[result_idx_].matrix().noalias() = affine[input_idx].matrix().inverse();
159 int main(
int argc,
char** argv)
161 testing::InitGoogleTest(&argc, argv);
162 return RUN_ALL_TESTS();
ScopedTimer(const char *msg="", double *gold_standard=nullptr)
EigenSTL::vector_Isometry3d transforms_
volatile size_t result_idx_
volatile size_t input_idx_
Representation of a robot's state. This includes position, velocity, acceleration and effort.
void setToRandomPositions()
Set all joints to random values. Values will be within default bounds.
void update(bool force=false)
Update all transforms.
moveit::core::RobotModelPtr loadTestingRobotModel(const std::string &robot_name)
Loads a robot from moveit_resources.
int main(int argc, char **argv)
TEST_F(Timing, stateUpdate)