41 #include <geometric_shapes/shape_operations.h>
42 #include <random_numbers/random_numbers.h>
47 static const std::string ROBOT_DESCRIPTION =
"robot_description";
50 static const int MAX_SEARCH_FACTOR_CLUTTER = 3;
53 static const int MAX_SEARCH_FACTOR_STATES = 30;
86 ROS_INFO(
"Cluttering scene...");
88 random_numbers::RandomNumberGenerator num_generator = random_numbers::RandomNumberGenerator(123);
97 current_state.setToDefaultValues(current_state.getJointModelGroup(
"panda_arm"),
"home");
98 current_state.update();
102 shapes::ShapeConstPtr shape;
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 };
111 while (added_objects < num_objects && i < num_objects * MAX_SEARCH_FACTOR_CLUTTER)
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);
118 quat.x() = num_generator.uniformReal(-1.0, 1.0);
119 quat.y() = num_generator.uniformReal(-1.0, 1.0);
120 quat.z() = num_generator.uniformReal(-1.0, 1.0);
121 quat.w() = num_generator.uniformReal(-1.0, 1.0);
129 shapes::Mesh* mesh = shapes::createMeshFromResource(kinect);
130 mesh->scale(num_generator.uniformReal(0.3, 1.0));
138 std::make_shared<shapes::Box>(num_generator.uniformReal(0.05, 0.2), num_generator.uniformReal(0.05, 0.2),
139 num_generator.uniformReal(0.05, 0.2));
145 name.append(std::to_string(i));
158 ROS_DEBUG_STREAM(
"Object was in collision, remove");
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) };
180 ROS_INFO_STREAM(
"Starting detection using " << (col_detector ==
CollisionDetector::FCL ?
"FCL" :
"Bullet"));
206 ros::WallTime start = ros::WallTime::now();
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);
223 double duration = (ros::WallTime::now() - start).toSec();
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)
257 while (robot_states.size() < num_states && i < num_states * MAX_SEARCH_FACTOR_STATES)
259 current_state.setToRandomPositions();
260 current_state.update();
262 scene->checkSelfCollision(req, res);
263 ROS_INFO_STREAM(
"Found state " << (res.
collision ?
"in collision" :
"not in collision"));
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]);
288 ROS_ERROR_STREAM(
"Did not find any correct states.");
292 int main(
int argc,
char** argv)
294 moveit::core::RobotModelPtr robot_model;
295 ros::init(argc, argv,
"compare_collision_checking_speed");
296 ros::NodeHandle node_handle;
298 ros::Publisher planning_scene_diff_publisher = node_handle.advertise<moveit_msgs::PlanningScene>(
"planning_scene", 1);
300 unsigned int trials = 10000;
302 ros::AsyncSpinner spinner(1);
304 ros::WallDuration sleep_t(2.5);
308 auto scene = std::make_shared<planning_scene::PlanningScene>(robot_model);
317 robot_model->getLinkModelNames(),
true) };
320 ROS_INFO(
"Starting...");
324 ros::Duration(0.5).sleep();
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");
Definition of a structure for the allowed collision matrix. All elements in the collision world are r...
static CollisionDetectorAllocatorPtr create()
Representation of a robot's state. This includes position, velocity, acceleration and effort.
PlanningSceneMonitor Subscribes to the topic planning_scene.
const planning_scene::PlanningScenePtr & getPlanningScene()
Avoid this function! Returns an unsafe pointer to the current planning scene.
@ UPDATE_SCENE
The entire scene was updated.
void startSceneMonitor(const std::string &scene_topic=DEFAULT_PLANNING_SCENE_TOPIC)
Start the scene monitor (ROS topic-based)
void startPublishingPlanningScene(SceneUpdateType event, const std::string &planning_scene_topic=MONITORED_PLANNING_SCENE_TOPIC)
Start publishing the maintained planning scene. The first message set out is a complete planning scen...
int main(int argc, char **argv)
void findStates(const RobotStateSelector desired_states, unsigned int num_states, const planning_scene::PlanningScenePtr &scene, std::vector< moveit::core::RobotState > &robot_states)
Samples valid states of the robot which can be in collision if desired.
CollisionDetector
Enumerates the available collision detectors.
RobotStateSelector
Defines a random robot state.
void runCollisionDetection(unsigned int trials, const planning_scene::PlanningScenePtr &scene, const std::vector< moveit::core::RobotState > &states, const CollisionDetector col_detector, bool only_self, bool distance=false)
Runs a collision detection benchmark and measures the time.
void clutterWorld(const planning_scene::PlanningScenePtr &planning_scene, const size_t num_objects, CollisionObjectType type)
Clutters the world of the planning scene with random objects in a certain area around the origin....
CollisionObjectType
Enumerates the different types of collision objects.
moveit::core::RobotModelPtr loadTestingRobotModel(const std::string &robot_name)
Loads a robot from moveit_resources.
This namespace includes the central class for representing planning contexts.
double distance(const urdf::Pose &transform)
Representation of a collision checking request.
bool contacts
If true, compute contacts. Otherwise only a binary collision yes/no is reported.
std::size_t max_contacts
Overall maximum number of contacts to compute.
std::size_t max_contacts_per_pair
Maximum number of contacts to compute per pair of bodies (multiple bodies may be in contact at differ...
bool distance
If true, compute proximity distance.
Representation of a collision checking result.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW void clear()
Clear a previously stored result.
bool collision
True if collision was found, false otherwise.
std::size_t contact_count
Number of contacts returned.