Skip to content

Commit

Permalink
Update tesseract_environment benchmarks
Browse files Browse the repository at this point in the history
  • Loading branch information
Levi-Armstrong committed Jan 6, 2025
1 parent ebcddc6 commit a701488
Show file tree
Hide file tree
Showing 3 changed files with 14 additions and 14 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ static void BM_CHECK_TRAJECTORY_CONTINUOUS_SS(benchmark::State& state,
static void BM_CHECK_TRAJECTORY_CONTINUOUS_MANIP(benchmark::State& state,
std::vector<tesseract_collision::ContactResultMap> contacts,
tesseract_collision::ContinuousContactManager::Ptr manager,
tesseract_kinematics::JointGroup::Ptr manip,
tesseract_kinematics::JointGroup::ConstPtr manip,
tesseract_common::TrajArray traj,
tesseract_collision::CollisionCheckConfig config,
bool log_level_debug)
Expand Down Expand Up @@ -106,7 +106,7 @@ static void BM_CHECK_TRAJECTORY_DISCRETE_SS(benchmark::State& state,
static void BM_CHECK_TRAJECTORY_DISCRETE_MANIP(benchmark::State& state,
std::vector<tesseract_collision::ContactResultMap> contacts,
tesseract_collision::DiscreteContactManager::Ptr manager,
tesseract_kinematics::JointGroup::Ptr manip,
tesseract_kinematics::JointGroup::ConstPtr manip,
tesseract_common::TrajArray traj,
tesseract_collision::CollisionCheckConfig config,
bool log_level_debug)
Expand Down Expand Up @@ -223,7 +223,7 @@ int main(int argc, char** argv)
tesseract_collision::DiscreteContactManager::Ptr discrete_manager = env->getDiscreteContactManager();
tesseract_collision::ContinuousContactManager::Ptr continuous_manager = env->getContinuousContactManager();
tesseract_scene_graph::StateSolver::Ptr state_solver = env->getStateSolver();
tesseract_kinematics::JointGroup::Ptr joint_group = env->getJointGroup("manipulator");
tesseract_kinematics::JointGroup::ConstPtr joint_group = env->getJointGroup("manipulator");
std::vector<tesseract_collision::ContactResultMap> contacts;
tesseract_collision::CollisionCheckConfig discrete_config;
discrete_config.type = CollisionEvaluatorType::DISCRETE;
Expand Down Expand Up @@ -255,7 +255,7 @@ int main(int argc, char** argv)
std::function<void(benchmark::State&,
std::vector<tesseract_collision::ContactResultMap>,
tesseract_collision::ContinuousContactManager::Ptr,
tesseract_kinematics::JointGroup::Ptr,
tesseract_kinematics::JointGroup::ConstPtr,
tesseract_common::TrajArray,
tesseract_collision::CollisionCheckConfig,
bool)>
Expand All @@ -272,7 +272,7 @@ int main(int argc, char** argv)
std::function<void(benchmark::State&,
std::vector<tesseract_collision::ContactResultMap>,
tesseract_collision::DiscreteContactManager::Ptr,
tesseract_kinematics::JointGroup::Ptr,
tesseract_kinematics::JointGroup::ConstPtr,
tesseract_common::TrajArray,
tesseract_collision::CollisionCheckConfig,
bool)>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ static void BM_SCENE_GRAPH_CLONE(benchmark::State& state, SceneGraph::Ptr sg)
}

/** @brief Benchmark that checks the Tesseract clone method*/
static void BM_JOINT_GROUP_COPY(benchmark::State& state, JointGroup::Ptr jg)
static void BM_JOINT_GROUP_COPY(benchmark::State& state, JointGroup::ConstPtr jg)
{
JointGroup::Ptr clone;
for (auto _ : state)
Expand All @@ -76,7 +76,7 @@ static void BM_JOINT_GROUP_COPY(benchmark::State& state, JointGroup::Ptr jg)
}
}

static void BM_KINEMATIC_GROUP_COPY(benchmark::State& state, KinematicGroup::Ptr kg)
static void BM_KINEMATIC_GROUP_COPY(benchmark::State& state, KinematicGroup::ConstPtr kg)
{
KinematicGroup::Ptr clone;
for (auto _ : state)
Expand All @@ -93,8 +93,8 @@ int main(int argc, char** argv)
Environment::Ptr env = std::make_shared<Environment>();
env->init(*scene_graph, srdf);
StateSolver::Ptr state_solver = env->getStateSolver();
JointGroup::Ptr joint_group = env->getJointGroup("manipulator");
KinematicGroup::Ptr kinematic_group = env->getKinematicGroup("manipulator");
JointGroup::ConstPtr joint_group = env->getJointGroup("manipulator");
KinematicGroup::ConstPtr kinematic_group = env->getKinematicGroup("manipulator");
//////////////////////////////////////
// Clone
//////////////////////////////////////
Expand Down Expand Up @@ -124,15 +124,15 @@ int main(int argc, char** argv)
}

{
std::function<void(benchmark::State&, JointGroup::Ptr)> BM_CLONE_FUNC = BM_JOINT_GROUP_COPY;
std::function<void(benchmark::State&, JointGroup::ConstPtr)> BM_CLONE_FUNC = BM_JOINT_GROUP_COPY;
std::string name = "BM_JOINT_GROUP_COPY";
benchmark::RegisterBenchmark(name.c_str(), BM_CLONE_FUNC, joint_group)
->UseRealTime()
->Unit(benchmark::TimeUnit::kMicrosecond);
}

{
std::function<void(benchmark::State&, KinematicGroup::Ptr)> BM_CLONE_FUNC = BM_KINEMATIC_GROUP_COPY;
std::function<void(benchmark::State&, KinematicGroup::ConstPtr)> BM_CLONE_FUNC = BM_KINEMATIC_GROUP_COPY;
std::string name = "BM_KINEMATIC_GROUP_COPY";
benchmark::RegisterBenchmark(name.c_str(), BM_CLONE_FUNC, kinematic_group)
->UseRealTime()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -93,7 +93,7 @@ static void BM_CALC_FWD_KIN_MANIP(benchmark::State& state, CalcStateFn fn, const
}

static void BM_GET_JACOBIAN_MANIP(benchmark::State& state,
tesseract_kinematics::JointGroup::Ptr manip,
tesseract_kinematics::JointGroup::ConstPtr manip,
const tesseract_common::TrajArray& traj,
std::string link_name)
{
Expand Down Expand Up @@ -158,7 +158,7 @@ int main(int argc, char** argv)
traj.col(i) = Eigen::VectorXd::LinSpaced(5, joint_start_pos(i), joint_end_pos(i));

tesseract_scene_graph::StateSolver::Ptr state_solver = env->getStateSolver();
tesseract_kinematics::JointGroup::Ptr joint_group = env->getJointGroup("manipulator");
tesseract_kinematics::JointGroup::ConstPtr joint_group = env->getJointGroup("manipulator");
std::string tip_link{ "tool0" };

//////////////////////////////////////
Expand Down Expand Up @@ -220,7 +220,7 @@ int main(int argc, char** argv)
}
{
std::function<void(
benchmark::State&, tesseract_kinematics::JointGroup::Ptr, const tesseract_common::TrajArray&, std::string)>
benchmark::State&, tesseract_kinematics::JointGroup::ConstPtr, const tesseract_common::TrajArray&, std::string)>
BM_CJ_MANIP = BM_GET_JACOBIAN_MANIP;
std::string name = "BM_GET_JACOBIAN_MANIP";
benchmark::RegisterBenchmark(name.c_str(), BM_CJ_MANIP, joint_group, traj, tip_link)
Expand Down

0 comments on commit a701488

Please sign in to comment.