47 static const rclcpp::Logger 
LOGGER = rclcpp::get_logger(
"moveit.ros.benchmarks.combine_predefined_poses_benchmark");
 
   59                               std::vector<StartState>& start_states, std::vector<PathConstraints>& 
path_constraints,
 
   60                               std::vector<PathConstraints>& goal_constraints,
 
   61                               std::vector<TrajectoryConstraints>& traj_constraints,
 
   62                               std::vector<BenchmarkRequest>& queries)
 override 
   66       psm_ = std::make_shared<planning_scene_monitor::PlanningSceneMonitor>(
node_, 
"robot_description");
 
   67     if (!psm_->newPlanningSceneMessage(scene_msg))
 
   69       RCLCPP_ERROR(LOGGER, 
"Failed to load planning scene");
 
   74     if (!psm_->getRobotModel())
 
   76       RCLCPP_ERROR(LOGGER, 
"Failed to load robot model");
 
   82     if (predefined_poses_group.empty())
 
   84       RCLCPP_WARN(LOGGER, 
"Parameter predefined_poses_group is not set, using default planning group instead");
 
   87     const auto& joint_model_group = psm_->getRobotModel()->getJointModelGroup(predefined_poses_group);
 
   88     if (!joint_model_group)
 
   90       RCLCPP_ERROR_STREAM(LOGGER, 
"Robot model has no joint model group named '" << predefined_poses_group << 
"'");
 
   97     goal_constraints.clear();
 
  102         RCLCPP_WARN_STREAM(LOGGER, 
"Failed to set robot state to named target '" << pose_id << 
"'");
 
  106       start_states.emplace_back();
 
  107       start_states.back().name = pose_id;
 
  111       goal_constraints.emplace_back();
 
  112       goal_constraints.back().name = pose_id;
 
  113       goal_constraints.back().constraints.push_back(
 
  116     if (start_states.empty() || goal_constraints.empty())
 
  118       RCLCPP_ERROR_STREAM(LOGGER, 
"Failed to init start and goal states from predefined_poses");
 
  124     traj_constraints.clear();
 
  130   planning_scene_monitor::PlanningSceneMonitorPtr psm_;
 
  134 int main(
int argc, 
char** argv)
 
  136   rclcpp::init(argc, argv);
 
  137   rclcpp::NodeOptions node_options;
 
  138   node_options.allow_undeclared_parameters(
true);
 
  139   node_options.automatically_declare_parameters_from_overrides(
true);
 
  140   rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared(
"moveit_run_benchmark", node_options);
 
  147   std::vector<std::string> planning_pipelines;
 
  153     RCLCPP_ERROR(LOGGER, 
"Failed to run all benchmarks");
 
int main(int argc, char **argv)
 
Representation of a robot's state. This includes position, velocity, acceleration and effort.
 
void setToDefaultValues()
Set all joints to their default positions. The default position is 0, or if that is not within bounds...
 
virtual bool runBenchmarks(const BenchmarkOptions &opts)
 
void initialize(const std::vector< std::string > &plugin_classes)
 
rclcpp::Node::SharedPtr node_
 
void getPlanningPipelineNames(std::vector< std::string > &planning_pipeline_names) const
Get all planning pipeline names.
 
const std::vector< std::string > & getPredefinedPoses() const
Get the names of all predefined poses to consider for planning.
 
const std::string & getGroupName() const
Get the name of the planning group to run the benchmark with.
 
const std::string & getPredefinedPosesGroup() const
Get the name of the planning group for which the predefined poses are defined.
 
CombinePredefinedPosesBenchmark(const rclcpp::Node::SharedPtr &node)
 
bool loadBenchmarkQueryData(const BenchmarkOptions &opts, moveit_msgs::msg::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.
 
moveit_msgs::msg::Constraints constructGoalConstraints(const moveit::core::RobotState &state, const moveit::core::JointModelGroup *jmg, double tolerance_below, double tolerance_above)
Generates a constraint message intended to be used as a goal constraint for a joint group....
 
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::msg::RobotState &robot_state, bool copy_attached_bodies=true)
Convert a MoveIt robot state to a robot state message.
 
const rclcpp::Logger LOGGER