97 current_state.setToDefaultValues(current_state.getJointModelGroup(
"panda_arm"),
"home");
98 current_state.update();
103 std::string kinect =
"package://moveit_resources_panda_description/meshes/collision/link5.stl";
105 Eigen::Quaterniond quat;
106 Eigen::Isometry3d pos{ Eigen::Isometry3d::Identity() };
108 size_t added_objects{ 0 };
114 pos.translation().x() = num_generator.
uniformReal(-1.0, 1.0);
115 pos.translation().y() = num_generator.
uniformReal(-1.0, 1.0);
116 pos.translation().z() = num_generator.
uniformReal(0.0, 1.0);
127 case CollisionObjectType::MESH:
135 case CollisionObjectType::BOX:
145 name.append(std::to_string(i));
164 ROS_INFO_STREAM(
"Cluttered the planning scene with " << added_objects <<
" objects");
174 const std::vector<moveit::core::RobotState>& states,
const CollisionDetector col_detector,
175 bool only_self,
bool distance =
false)
178 scene->getRobotModel()->getLinkModelNames(),
true) };
207 for (
unsigned int i = 0; i < trials; ++i)
209 for (
auto& state : states)
215 scene->checkSelfCollision(req, res);
219 scene->checkCollision(req, res, state);
224 ROS_INFO(
"Performed %lf collision checks per second", (
double)trials * states.size() /
duration);
225 ROS_INFO_STREAM(
"Total number was " << trials * states.size() <<
" checks.");
226 ROS_INFO_STREAM(
"We had " << states.size() <<
" different robot states which were "
232 ROS_INFO_STREAM(
"Between: " << contact.first.first <<
" and " << contact.first.second);
233 std_msgs::ColorRGBA red;
238 scene->setObjectColor(contact.first.first, red);
239 scene->setObjectColor(contact.first.second, red);
242 scene->setCurrentState(states.back());
251 const planning_scene::PlanningScenePtr& scene, std::vector<moveit::core::RobotState>& robot_states)
259 current_state.setToRandomPositions();
260 current_state.update();
262 scene->checkSelfCollision(req, res);
265 switch (desired_states)
269 robot_states.push_back(current_state);
273 robot_states.push_back(current_state);
276 robot_states.push_back(current_state);
282 if (!robot_states.empty())
284 scene->setCurrentState(robot_states[0]);
292 int main(
int argc,
char** argv)
294 moveit::core::RobotModelPtr robot_model;
295 ros::init(argc, argv,
"compare_collision_checking_speed");
298 ros::Publisher planning_scene_diff_publisher = node_handle.
advertise<moveit_msgs::PlanningScene>(
"planning_scene", 1);
300 unsigned int trials = 10000;
317 robot_model->getLinkModelNames(),
true) };
327 current_state.setToDefaultValues(current_state.getJointModelGroup(
"panda_arm"),
"home");
328 current_state.update();
330 std::vector<moveit::core::RobotState> sampled_states;
331 sampled_states.push_back(current_state);
333 ROS_INFO(
"Starting benchmark: Robot in empty world, only self collision check");
341 ROS_INFO(
"Starting benchmark: Robot in cluttered world, no collision with world");
346 double joint_2 = 1.5;
347 current_state.setJointPositions(
"panda_joint2", &joint_2);
348 current_state.update();
350 std::vector<moveit::core::RobotState> sampled_states_2;
351 sampled_states_2.push_back(current_state);
353 ROS_INFO(
"Starting benchmark: Robot in cluttered world, in collision with world");
358 node_handle.
getParam(
"/compare_collision_checking_speed/visualization", visualize);
362 moveit_msgs::PlanningScene planning_scene_msg;
364 planning_scene_diff_publisher.
publish(planning_scene_msg);
369 ROS_ERROR(
"Planning scene not configured");