CombinePredefinedPosesBenchmark.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2019, PickNik LLC
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the PickNik LLC nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Henning Kayser */
36 /* Description: A simple benchmark that plans trajectories for all combinations of specified predefined poses */
37 
38 // MoveIt Benchmark
41 
42 // MoveIt
46 
47 namespace moveit_ros_benchmarks
48 {
49 constexpr char LOGNAME[] = "combine_predefined_poses_benchmark";
50 class CombinePredefinedPosesBenchmark : public BenchmarkExecutor
51 {
52 public:
53  bool loadBenchmarkQueryData(const BenchmarkOptions& opts, moveit_msgs::PlanningScene& scene_msg,
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
58  {
59  // Load planning scene
60  if (!psm_)
61  psm_ = std::make_shared<planning_scene_monitor::PlanningSceneMonitor>("robot_description");
62  if (!psm_->newPlanningSceneMessage(scene_msg))
63  {
64  ROS_ERROR_NAMED(LOGNAME, "Failed to load planning scene");
65  return false;
66  }
67 
68  // Load robot model
69  if (!psm_->getRobotModel())
70  {
71  ROS_ERROR_NAMED(LOGNAME, "Failed to load robot model");
72  return false;
73  }
74 
75  // Select planning group to use for predefined poses
76  std::string predefined_poses_group = opts.getPredefinedPosesGroup();
77  if (predefined_poses_group.empty())
78  {
79  ROS_WARN_NAMED(LOGNAME, "Parameter predefined_poses_group is not set, using default planning group instead");
80  predefined_poses_group = opts.getGroupName();
81  }
82  const auto& joint_model_group = psm_->getRobotModel()->getJointModelGroup(predefined_poses_group);
83  if (!joint_model_group)
84  {
85  ROS_ERROR_STREAM_NAMED(LOGNAME, "Robot model has no joint model group named '" << predefined_poses_group << "'");
86  return false;
87  }
88 
89  // Iterate over all predefined poses and use each as start and goal states
90  moveit::core::RobotState robot_state(psm_->getRobotModel());
91  start_states.clear();
92  goal_constraints.clear();
93  for (const auto& pose_id : opts.getPredefinedPoses())
94  {
95  if (!robot_state.setToDefaultValues(joint_model_group, pose_id))
96  {
97  ROS_WARN_STREAM_NAMED(LOGNAME, "Failed to set robot state to named target '" << pose_id << "'");
98  continue;
99  }
100  // Create start state
101  start_states.emplace_back();
102  start_states.back().name = pose_id;
103  moveit::core::robotStateToRobotStateMsg(robot_state, start_states.back().state);
104 
105  // Create goal constraints
106  goal_constraints.emplace_back();
107  goal_constraints.back().name = pose_id;
108  goal_constraints.back().constraints.push_back(
109  kinematic_constraints::constructGoalConstraints(robot_state, joint_model_group));
110  }
111  if (start_states.empty() || goal_constraints.empty())
112  {
113  ROS_ERROR_NAMED(LOGNAME, "Failed to init start and goal states from predefined_poses");
114  return false;
115  }
116 
117  // We don't use path/trajectory constraints or custom queries
118  path_constraints.clear();
119  traj_constraints.clear();
120  queries.clear();
121  return true;
122  }
123 
124 private:
125  planning_scene_monitor::PlanningSceneMonitorPtr psm_;
126 };
127 } // namespace moveit_ros_benchmarks
128 
129 int main(int argc, char** argv)
130 {
131  ros::init(argc, argv, "moveit_run_benchmark");
133  spinner.start();
134 
135  // Read benchmark options from param server
137  // Setup benchmark server
139 
140  std::vector<std::string> planning_pipelines;
141  opts.getPlanningPipelineNames(planning_pipelines);
142  server.initialize(planning_pipelines);
143 
144  // Running benchmarks
145  if (!server.runBenchmarks(opts))
146  ROS_ERROR("Failed to run all benchmarks");
147 }
BenchmarkOptions.h
moveit_ros_benchmarks::CombinePredefinedPosesBenchmark
Definition: CombinePredefinedPosesBenchmark.cpp:82
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
moveit_ros_benchmarks::BenchmarkExecutor::runBenchmarks
virtual bool runBenchmarks(const BenchmarkOptions &opts)
Definition: BenchmarkExecutor.cpp:204
moveit_ros_benchmarks::CombinePredefinedPosesBenchmark::psm_
planning_scene_monitor::PlanningSceneMonitorPtr psm_
Definition: CombinePredefinedPosesBenchmark.cpp:157
utils.h
ros::AsyncSpinner
kinematic_constraints::constructGoalConstraints
moveit_msgs::Constraints constructGoalConstraints(const moveit::core::RobotState &state, const moveit::core::JointModelGroup *jmg, double tolerance=std::numeric_limits< double >::epsilon())
ROS_ERROR_NAMED
#define ROS_ERROR_NAMED(name,...)
moveit::core::RobotState
spinner
void spinner()
moveit_ros_benchmarks::LOGNAME
constexpr char LOGNAME[]
Definition: CombinePredefinedPosesBenchmark.cpp:81
planning_scene_monitor.h
ROS_ERROR_STREAM_NAMED
#define ROS_ERROR_STREAM_NAMED(name, args)
moveit_ros_benchmarks::BenchmarkExecutor::initialize
void initialize(const std::vector< std::string > &plugin_classes)
Definition: BenchmarkExecutor.cpp:101
ROS_ERROR
#define ROS_ERROR(...)
ROS_WARN_STREAM_NAMED
#define ROS_WARN_STREAM_NAMED(name, args)
ros::this_node::getName
const ROSCPP_DECL std::string & getName()
moveit_ros_benchmarks::CombinePredefinedPosesBenchmark::loadBenchmarkQueryData
bool loadBenchmarkQueryData(const BenchmarkOptions &opts, moveit_msgs::PlanningScene &scene_msg, std::vector< StartState > &start_states, std::vector< PathConstraints > &path_constraints, std::vector< PathConstraints > &goal_constraints, std::vector< TrajectoryConstraints > &traj_constraints, std::vector< BenchmarkRequest > &queries) override
Initialize benchmark query data from start states and constraints.
Definition: CombinePredefinedPosesBenchmark.cpp:85
ROS_WARN_NAMED
#define ROS_WARN_NAMED(name,...)
conversions.h
moveit_ros_benchmarks::BenchmarkOptions
Definition: BenchmarkOptions.h:79
main
int main(int argc, char **argv)
Definition: CombinePredefinedPosesBenchmark.cpp:129
moveit_ros_benchmarks::BenchmarkOptions::getPlanningPipelineNames
void getPlanningPipelineNames(std::vector< std::string > &planning_pipeline_names) const
Get all planning pipeline names.
Definition: BenchmarkOptions.cpp:160
moveit::core::robotStateToRobotStateMsg
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::RobotState &robot_state, bool copy_attached_bodies=true)
moveit_ros_benchmarks
Definition: BenchmarkExecutor.h:57
BenchmarkExecutor.h


benchmarks
Author(s): Ryan Luna
autogenerated on Sat May 3 2025 02:27:17