00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00037 #include <ros/ros.h>
00038 #include <planning_environment/monitors/collision_space_monitor.h>
00039 #include <visualization_msgs/Marker.h>
00040 #include <boost/thread.hpp>
00041
00042 class CollisionTestSpeed
00043 {
00044 public:
00045
00046 CollisionTestSpeed(void)
00047 {
00048 vmPub_ = nh_.advertise<visualization_msgs::Marker>("visualization_marker", 10240);
00049 cm_ = new planning_environment::CollisionModels("robot_description", 1.0, 0.02);
00050 id_ = 1;
00051 }
00052
00053 virtual ~CollisionTestSpeed(void)
00054 {
00055 delete cm_;
00056 }
00057
00058 void testPointCloud(void)
00059 {
00060 if (!cm_->loadedModels())
00061 return;
00062
00063 planning_models::KinematicState state(cm_->getKinematicModel());
00064
00065 collision_space::EnvironmentModel *em = cm_->getODECollisionModel().get();
00066 em->setSelfCollision(false);
00067
00068 em->updateRobotModel(&state);
00069 ROS_INFO("Collision (should be 0): %d", em->isCollision());
00070
00071 const int n = 10000;
00072
00073 std::vector<shapes::Shape*> spheres;
00074 std::vector<btTransform> poses;
00075
00076 for (int i = 0 ; i < n ; ++i)
00077 {
00078 btTransform pos;
00079 pos.setIdentity();
00080 do
00081 {
00082 shapes::Sphere* obj = new shapes::Sphere(0.02);
00083 em->clearObjects();
00084 pos.setOrigin(btVector3(uniform(1.5), uniform(1.5), uniform(1.5)));
00085 em->addObject("points", obj, pos);
00086 if (n < 100)
00087 {
00088 collision_space::EnvironmentModel *clone = em->clone();
00089 clone->updateRobotModel(&state);
00090 if (clone->isCollision() != em->isCollision())
00091 ROS_ERROR("Error in cloning");
00092 delete clone;
00093 }
00094 }
00095 while(em->isCollision());
00096 spheres.push_back(new shapes::Sphere(0.02));
00097 poses.push_back(pos);
00098 }
00099
00100 em->clearObjects();
00101 em->addObjects("points", spheres, poses);
00102 ROS_INFO("Added %d spheres", n);
00103
00104 ROS_INFO("Collision (should be 0): %d", em->isCollision());
00105 collision_space::EnvironmentModel *clone = em->clone();
00106 clone->updateRobotModel(&state);
00107 clone->setVerbose(true);
00108 ROS_INFO("Collision of clone (should be 0): %d", clone->isCollision());
00109 delete clone;
00110
00111 const unsigned int K = 10000;
00112
00113 ros::WallTime tm = ros::WallTime::now();
00114 for (unsigned int i = 0 ; i < K ; ++i)
00115 em->isCollision();
00116 ROS_INFO("%f collision tests per second (without self collision checking)", (double)K/(ros::WallTime::now() - tm).toSec());
00117
00118 em->setSelfCollision(true);
00119 tm = ros::WallTime::now();
00120 for (unsigned int i = 0 ; i < K ; ++i)
00121 em->isCollision();
00122 ROS_INFO("%f collision tests per second (with self collision checking)", (double)K/(ros::WallTime::now() - tm).toSec());
00123
00124 tm = ros::WallTime::now();
00125 for (unsigned int i = 0 ; i < K ; ++i)
00126 em->isSelfCollision();
00127 ROS_INFO("%f collision tests per second (only self collision checking)", (double)K/(ros::WallTime::now() - tm).toSec());
00128
00129 const unsigned int C = 100;
00130 tm = ros::WallTime::now();
00131 for (unsigned int i = 0 ; i < C ; ++i)
00132 {
00133 collision_space::EnvironmentModel *clone = em->clone();
00134 clone->updateRobotModel(&state);
00135 if (em->isCollision() != clone->isCollision())
00136 ROS_ERROR("Cloning is problematic");
00137 delete clone;
00138 }
00139 ROS_INFO("%f collision tests + clones per second", (double)C/(ros::WallTime::now() - tm).toSec());
00140 }
00141
00142 void testCollision(void)
00143 {
00144 if (!cm_->loadedModels())
00145 return;
00146
00147 planning_models::KinematicState state(cm_->getKinematicModel());
00148 collision_space::EnvironmentModel *em = cm_->getODECollisionModel()->clone();
00149 em->setSelfCollision(false);
00150
00151 em->updateRobotModel(&state);
00152 ROS_INFO("Collision (should be 0): %d", em->isCollision());
00153
00154 const int n = 10000;
00155
00156 for (int i = 0 ; i < n ; ++i)
00157 {
00158 btTransform pos;
00159 pos.setIdentity();
00160 do
00161 { shapes::Sphere* obj = new shapes::Sphere(0.02);
00162 em->clearObjects();
00163 pos.setOrigin(btVector3(uniform(1.5), uniform(1.5), uniform(1.5)));
00164 em->addObject("points", obj, pos);
00165 }
00166 while(!em->isCollision());
00167 sendPoint(pos.getOrigin().x(), pos.getOrigin().y(), pos.getOrigin().z());
00168 }
00169
00170 ROS_INFO("Added %d points", n);
00171
00172 delete em;
00173 }
00174
00175 void collisionThread(int tid, collision_space::EnvironmentModel *emx)
00176 {
00177 planning_models::KinematicState state(emx->getRobotModel());
00178
00179 collision_space::EnvironmentModel *em = emx->clone();
00180 em->updateRobotModel(&state);
00181
00182 ROS_INFO("Thread %d using instance %p, collision = %d (should be 0)", tid, em, em->isCollision());
00183
00184 const unsigned int K = 10000;
00185
00186 sleep(1);
00187
00188 ros::WallTime tm = ros::WallTime::now();
00189 for (unsigned int i = 0 ; i < K ; ++i)
00190 em->isCollision();
00191 ROS_INFO("Thread %d: %f collision tests per second (with self collision checking)", tid, (double)K/(ros::WallTime::now() - tm).toSec());
00192
00193 delete em;
00194 }
00195
00196 void collisionSetupThread(collision_space::EnvironmentModel *em)
00197 {
00198 const int n = 10000;
00199
00200 std::vector<shapes::Shape*> spheres;
00201 std::vector<btTransform> poses;
00202
00203 for (int i = 0 ; i < n ; ++i)
00204 {
00205 btTransform pos;
00206 pos.setIdentity();
00207 do
00208 { shapes::Sphere* obj = new shapes::Sphere(0.02);
00209 em->clearObjects();
00210 pos.setOrigin(btVector3(uniform(1.5), uniform(1.5), uniform(1.5)));
00211 em->addObject("points", obj, pos);
00212 }
00213 while(em->isCollision());
00214 spheres.push_back(new shapes::Sphere(0.02));
00215 poses.push_back(pos);
00216 }
00217
00218 em->clearObjects();
00219 em->addObjects("points", spheres, poses);
00220 ROS_INFO("Added %d points", n);
00221 ROS_INFO("Collision after thread setup (should be 0): %d", em->isCollision());
00222
00223 }
00224
00225 void testThreads(void)
00226 {
00227 if (!cm_->loadedModels())
00228 return;
00229 planning_models::KinematicState state(cm_->getKinematicModel());
00230 collision_space::EnvironmentModel *em = cm_->getODECollisionModel().get();
00231 em->setSelfCollision(true);
00232 em->updateRobotModel(&state);
00233
00234 boost::thread t(boost::bind(&CollisionTestSpeed::collisionSetupThread, this, em));
00235 t.join();
00236
00237 int nt = 2;
00238 std::vector<boost::thread*> th(nt);
00239 for (int i = 0 ; i < nt ; ++i)
00240 th[i] = new boost::thread(boost::bind(&CollisionTestSpeed::collisionThread, this, i, em));
00241 for (int i = 0 ; i < nt ; ++i)
00242 {
00243 th[i]->join();
00244 delete th[i];
00245 }
00246 }
00247
00248 protected:
00249
00250 void sendPoint(double x, double y, double z)
00251 {
00252 visualization_msgs::Marker mk;
00253
00254 mk.header.stamp = ros::Time::now();
00255
00256 mk.header.frame_id = "base_link";
00257
00258 mk.ns = "test_self_filter";
00259 mk.id = id_++;
00260 mk.type = visualization_msgs::Marker::SPHERE;
00261 mk.action = visualization_msgs::Marker::ADD;
00262 mk.pose.position.x = x;
00263 mk.pose.position.y = y;
00264 mk.pose.position.z = z;
00265 mk.pose.orientation.w = 1.0;
00266
00267 mk.scale.x = mk.scale.y = mk.scale.z = 0.01;
00268
00269 mk.color.a = 1.0;
00270 mk.color.r = 1.0;
00271 mk.color.g = 0.04;
00272 mk.color.b = 0.04;
00273
00274 vmPub_.publish(mk);
00275 }
00276
00277
00278
00279 double uniform(double magnitude)
00280 {
00281 return (2.0 * drand48() - 1.0) * magnitude;
00282 }
00283
00284 ros::Publisher vmPub_;
00285 ros::NodeHandle nh_;
00286 planning_environment::CollisionModels *cm_;
00287 int id_;
00288
00289 };
00290
00291
00292 int main(int argc, char **argv)
00293 {
00294 ros::init(argc, argv, "CollisionTestSpeed");
00295
00296 CollisionTestSpeed cts;
00297
00298
00299 cts.testCollision();
00300
00301
00302 ROS_INFO("Done");
00303 ros::spin();
00304
00305 return 0;
00306 }