57 const planning_scene::PlanningSceneConstPtr& scene,
const std::string& group,
58 const std::string& link_name,
unsigned int sample_count,
59 visualization_msgs::msg::MarkerArray& markers)
62 link_name, sample_count, markers);
97 const std::string& link_name,
unsigned int sample_count,
98 visualization_msgs::msg::MarkerArray& markers)
102 RCLCPP_ERROR(getLogger(),
"No sampler specified for visualizing distribution of samples");
109 std_msgs::msg::ColorRGBA color;
114 for (
unsigned int i = 0; i < sample_count; ++i)
116 if (!sampler->sample(ks))
119 visualization_msgs::msg::Marker mk;
120 mk.header.stamp = rclcpp::Clock(RCL_ROS_TIME).now();
121 mk.header.frame_id = sampler->getJointModelGroup()->getParentModel().getModelFrame();
122 mk.ns =
"constraint_samples";
124 mk.type = visualization_msgs::msg::Marker::SPHERE;
125 mk.action = visualization_msgs::msg::Marker::ADD;
126 mk.pose.position.x = pos.x();
127 mk.pose.position.y = pos.y();
128 mk.pose.position.z = pos.z();
129 mk.pose.orientation.w = 1.0;
130 mk.scale.x = mk.scale.y = mk.scale.z = 0.035;
132 mk.lifetime = rclcpp::Duration::from_seconds(30);
133 markers.markers.push_back(mk);