50 bool hasPointDepthSensor;
51 bool hasPointDisparitySensor;
56 std::string outputFilename;
57 arg.
param(
"simSteps", simSteps, 100,
"number of simulation steps");
58 arg.
param(
"nLandmarks", nlandmarks, 1000,
"number of landmarks");
59 arg.
param(
"worldSize", worldSize, 25.0,
"size of the world");
60 arg.
param(
"hasOdom", hasOdom,
false,
"the robot has an odometry" );
61 arg.
param(
"hasPointSensor", hasPointSensor,
false,
"the robot has a point sensor" );
62 arg.
param(
"hasPointDepthSensor", hasPointDepthSensor,
false,
"the robot has a point sensor" );
63 arg.
param(
"hasPointDisparitySensor", hasPointDisparitySensor,
false,
"the robot has a point sensor" );
64 arg.
param(
"hasPoseSensor", hasPoseSensor,
false,
"the robot has a pose sensor" );
65 arg.
param(
"hasCompass", hasCompass,
false,
"the robot has a compass");
66 arg.
param(
"hasGPS", hasGPS,
false,
"the robot has a GPS");
67 arg.
paramLeftOver(
"graph-output", outputFilename,
"simulator_out.g2o",
"graph file which will be written",
true);
71 std::mt19937 generator;
74 for (
int i=0; i<nlandmarks; i++){
79 landmark->
vertex()->setEstimate(Vector3d(x,y,z));
80 world.addWorldObject(landmark);
82 Robot3D robot(&world,
"myRobot");
83 world.addRobot(&robot);
86 ss <<
"-ws" << worldSize;
87 ss <<
"-nl" << nlandmarks;
88 ss <<
"-steps" << simSteps;
92 robot.addSensor(odometrySensor);
99 robot.addSensor(pointSensor);
100 Eigen::Isometry3d cameraPose;
107 cameraPose.translation() = Vector3d(0.,0.,0.3);
112 if (hasPointDisparitySensor){
117 robot.addSensor(disparitySensor);
118 Eigen::Isometry3d cameraPose;
124 cameraPose.translation() = Vector3d(0.,0.,0.3);
129 if (hasPointDepthSensor){
134 robot.addSensor(depthSensor);
135 Eigen::Isometry3d cameraPose;
141 cameraPose.translation() = Vector3d(0.,0.,0.3);
148 robot.addSensor(poseSensor);
153 #ifdef _POSE_PRIOR_SENSOR 155 robot.addSensor(&posePriorSensor);
157 Eigen::Isometry3d cameraPose;
163 cameraPose.translation() = Vector3d(0.,0.,0.3);
164 posePriorSensor.offsetParam()->setOffset(cameraPose);
168 #ifdef _POSE_SENSOR_OFFSET 173 robot.addSensor(&poseSensor);
175 Eigen::Isometry3d cameraPose;
181 cameraPose.translation() = Vector3d(0.,0.,0.3);
182 poseSensor.offsetParam1()->setOffset(cameraPose);
183 poseSensor.offsetParam2()->setOffset(cameraPose);
188 robot.move(Eigen::Isometry3d::Identity());
189 double pStraight=0.7;
190 Eigen::Isometry3d moveStraight = Eigen::Isometry3d::Identity(); moveStraight.translation() = Vector3d(1., 0., 0.);
192 Eigen::Isometry3d moveLeft = Eigen::Isometry3d::Identity(); moveLeft = AngleAxisd(
M_PI/2, Vector3d::UnitZ());
194 Eigen::Isometry3d moveRight = Eigen::Isometry3d::Identity(); moveRight = AngleAxisd(-
M_PI/2,Vector3d::UnitZ());
196 Eigen::Matrix3d dtheta = Eigen::Matrix3d::Identity();
197 for (
int i=0; i<simSteps; i++){
198 bool boundariesReached =
true;
201 const Eigen::Isometry3d& pose = robot.pose();
202 if (pose.translation().x() < -.5*worldSize){
203 dtheta = AngleAxisd(0,Vector3d::UnitZ());
204 }
else if (pose.translation().x() > .5*worldSize){
205 dtheta = AngleAxisd(-
M_PI,Vector3d::UnitZ());
206 }
else if (pose.translation().y() < -.5*worldSize){
207 dtheta = AngleAxisd(
M_PI/2,Vector3d::UnitZ());
208 }
else if (pose.translation().y() > .5*worldSize){
209 dtheta = AngleAxisd(-
M_PI/2,Vector3d::UnitZ());
211 boundariesReached=
false;
214 Eigen::Isometry3d move = Eigen::Isometry3d::Identity();
215 if (boundariesReached){
216 Eigen::Matrix3d mTheta = pose.rotation().inverse() * dtheta;
218 AngleAxisd aa(mTheta);
219 if (aa.angle()<std::numeric_limits<double>::epsilon()){
220 move.translation() = Vector3d(1., 0., 0.);
224 if (sampled<pStraight)
226 else if (sampled<pStraight+pLeft)
234 robot.relativeMove(move);
239 string fname=outputFilename + ss.str() +
".g2o";
241 ofstream testStream(outputFilename.c_str());
242 graph.
save(testStream);
void setMinRange(double minRange_)
WorldObject< VertexPointXYZ > WorldObjectTrackXYZ
Command line parsing of argc and argv.
void setMaxRange(double maxRange_)
bool parseArgs(int argc, char **argv, bool exitOnError=true)
virtual bool save(std::ostream &os, int level=0) const
save the graph to a stream. Again uses the Factory system.
void setOffset(const Isometry3D &offset_=Isometry3D::Identity())
void paramLeftOver(const std::string &name, std::string &p, const std::string &defValue, const std::string &desc, bool optional=false)
void param(const std::string &name, bool &p, bool defValue, const std::string &desc)
ParameterSE3Offset * offsetParam()
ParameterSE3Offset * offsetParam()
ParameterSE3Offset * offsetParam()
Protocol The SLAM executable accepts such as solving the and retrieving or vertices in the graph
double sampleUniform(double min, double max, std::mt19937 *generator)