49 constexpr
char LOGNAME[] =
"combine_predefined_poses_benchmark";
50 class CombinePredefinedPosesBenchmark :
public BenchmarkExecutor
54 std::vector<StartState>& start_states, std::vector<PathConstraints>& path_constraints,
55 std::vector<PathConstraints>& goal_constraints,
56 std::vector<TrajectoryConstraints>& traj_constraints,
57 std::vector<BenchmarkRequest>& queries)
override
61 psm_ = std::make_shared<planning_scene_monitor::PlanningSceneMonitor>(
"robot_description");
62 if (!
psm_->newPlanningSceneMessage(scene_msg))
69 if (!
psm_->getRobotModel())
76 std::string predefined_poses_group = opts.getPredefinedPosesGroup();
77 if (predefined_poses_group.empty())
79 ROS_WARN_NAMED(
LOGNAME,
"Parameter predefined_poses_group is not set, using default planning group instead");
80 predefined_poses_group = opts.getGroupName();
82 const auto& joint_model_group =
psm_->getRobotModel()->getJointModelGroup(predefined_poses_group);
83 if (!joint_model_group)
92 goal_constraints.clear();
93 for (
const auto& pose_id : opts.getPredefinedPoses())
95 if (!robot_state.setToDefaultValues(joint_model_group, pose_id))
101 start_states.emplace_back();
102 start_states.back().name = pose_id;
106 goal_constraints.emplace_back();
107 goal_constraints.back().name = pose_id;
108 goal_constraints.back().constraints.push_back(
111 if (start_states.empty() || goal_constraints.empty())
118 path_constraints.clear();
119 traj_constraints.clear();
125 planning_scene_monitor::PlanningSceneMonitorPtr
psm_;
129 int main(
int argc,
char** argv)
131 ros::init(argc, argv,
"moveit_run_benchmark");
140 std::vector<std::string> planning_pipelines;
146 ROS_ERROR(
"Failed to run all benchmarks");