g2o
test_simulator3d.cpp
Go to the documentation of this file.
1 // g2o - General Graph Optimization
2 // Copyright (C) 2011 G. Grisetti, R. Kuemmerle, W. Burgard
3 // All rights reserved.
4 //
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are
7 // met:
8 //
9 // * Redistributions of source code must retain the above copyright notice,
10 // this list of conditions and the following disclaimer.
11 // * Redistributions in binary form must reproduce the above copyright
12 // notice, this list of conditions and the following disclaimer in the
13 // documentation and/or other materials provided with the distribution.
14 //
15 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS
16 // IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED
17 // TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A
18 // PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
19 // HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
20 // SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED
21 // TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
22 // PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
23 // LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
24 // NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 
27 #include <cstdlib>
28 #include "g2o/stuff/command_args.h"
29 #include "g2o/stuff/sampler.h"
30 #include "simulator3d.h"
32 #include <iostream>
33 #include <fstream>
34 
35 //#define _POSE_SENSOR_OFFSET
36 //#define _POSE_PRIOR_SENSOR
37 
38 using namespace g2o;
39 using namespace std;
40 using namespace Eigen;
41 
42 int main(int argc, char** argv) {
43  CommandArgs arg;
44  int nlandmarks;
45  int simSteps;
46  double worldSize;
47  bool hasOdom;
48  bool hasPoseSensor;
49  bool hasPointSensor;
50  bool hasPointDepthSensor;
51  bool hasPointDisparitySensor;
52  bool hasCompass;
53  bool hasGPS;
54 
55 
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);
68 
69  arg.parseArgs(argc, argv);
70 
71  std::mt19937 generator;
73  World world(&graph);
74  for (int i=0; i<nlandmarks; i++){
76  double x = sampleUniform(-.5, .5, &generator)*worldSize;
77  double y = sampleUniform(-.5, .5, &generator)*worldSize;
78  double z = sampleUniform(-.5, .5);
79  landmark->vertex()->setEstimate(Vector3d(x,y,z));
80  world.addWorldObject(landmark);
81  }
82  Robot3D robot(&world, "myRobot");
83  world.addRobot(&robot);
84 
85  stringstream ss;
86  ss << "-ws" << worldSize;
87  ss << "-nl" << nlandmarks;
88  ss << "-steps" << simSteps;
89 
90  if (hasOdom) {
91  SensorOdometry3D* odometrySensor=new SensorOdometry3D("odometry");
92  robot.addSensor(odometrySensor);
93  ss << "-odom";
94  }
95 
96  if (hasPointSensor) {
97  SensorPointXYZ* pointSensor = new SensorPointXYZ("pointSensor");
98  pointSensor->setFov(M_PI/4);
99  robot.addSensor(pointSensor);
100  Eigen::Isometry3d cameraPose;
101  Eigen::Matrix3d R;
102  R << 0, 0, 1,
103  -1, 0, 0,
104  0, -1, 0;
105  pointSensor->setMaxRange(2.);
106  cameraPose = R;
107  cameraPose.translation() = Vector3d(0.,0.,0.3);
108  pointSensor->offsetParam()->setOffset(cameraPose);
109  ss << "-pointXYZ";
110  }
111 
112  if (hasPointDisparitySensor){
113  SensorPointXYZDisparity* disparitySensor = new SensorPointXYZDisparity("disparitySensor");
114  disparitySensor->setFov(M_PI/4);
115  disparitySensor->setMinRange(0.5);
116  disparitySensor->setMaxRange(2.);
117  robot.addSensor(disparitySensor);
118  Eigen::Isometry3d cameraPose;
119  Eigen::Matrix3d R;
120  R << 0, 0, 1,
121  -1, 0, 0,
122  0, -1, 0;
123  cameraPose = R;
124  cameraPose.translation() = Vector3d(0.,0.,0.3);
125  disparitySensor->offsetParam()->setOffset(cameraPose);
126  ss << "-disparity";
127  }
128 
129  if (hasPointDepthSensor){
130  SensorPointXYZDepth* depthSensor = new SensorPointXYZDepth("depthSensor");
131  depthSensor->setFov(M_PI/4);
132  depthSensor->setMinRange(0.5);
133  depthSensor->setMaxRange(2.);
134  robot.addSensor(depthSensor);
135  Eigen::Isometry3d cameraPose;
136  Eigen::Matrix3d R;
137  R << 0, 0, 1,
138  -1, 0, 0,
139  0, -1, 0;
140  cameraPose = R;
141  cameraPose.translation() = Vector3d(0.,0.,0.3);
142  depthSensor->offsetParam()->setOffset(cameraPose);
143  ss << "-depth";
144  }
145 
146  if (hasPoseSensor){
147  SensorPose3D* poseSensor = new SensorPose3D("poseSensor");
148  robot.addSensor(poseSensor);
149  poseSensor->setMaxRange(5);
150  ss << "-pose";
151  }
152 
153 #ifdef _POSE_PRIOR_SENSOR
154  SensorSE3Prior posePriorSensor("posePriorSensor");
155  robot.addSensor(&posePriorSensor);
156  {
157  Eigen::Isometry3d cameraPose;
158  Eigen::Matrix3d R;
159  R << 0, 0, 1,
160  -1, 0, 0,
161  0, -1, 0;
162  cameraPose = R;
163  cameraPose.translation() = Vector3d(0.,0.,0.3);
164  posePriorSensor.offsetParam()->setOffset(cameraPose);
165  }
166 #endif
167 
168 #ifdef _POSE_SENSOR_OFFSET
169  SensorPose3DOffset poseSensor("poseSensor");
170  poseSensor.setFov(M_PI/4);
171  poseSensor.setMinRange(0.5);
172  poseSensor.setMaxRange(5);
173  robot.addSensor(&poseSensor);
174  if(0){
175  Eigen::Isometry3d cameraPose;
176  Eigen::Matrix3d R;
177  R << 0, 0, 1,
178  -1, 0, 0,
179  0, -1, 0;
180  cameraPose = R;
181  cameraPose.translation() = Vector3d(0.,0.,0.3);
182  poseSensor.offsetParam1()->setOffset(cameraPose);
183  poseSensor.offsetParam2()->setOffset(cameraPose);
184  }
185 #endif
186 
187 
188  robot.move(Eigen::Isometry3d::Identity());
189  double pStraight=0.7;
190  Eigen::Isometry3d moveStraight = Eigen::Isometry3d::Identity(); moveStraight.translation() = Vector3d(1., 0., 0.);
191  double pLeft=0.15;
192  Eigen::Isometry3d moveLeft = Eigen::Isometry3d::Identity(); moveLeft = AngleAxisd(M_PI/2, Vector3d::UnitZ());
193  //double pRight=0.15;
194  Eigen::Isometry3d moveRight = Eigen::Isometry3d::Identity(); moveRight = AngleAxisd(-M_PI/2,Vector3d::UnitZ());
195 
196  Eigen::Matrix3d dtheta = Eigen::Matrix3d::Identity();
197  for (int i=0; i<simSteps; i++){
198  bool boundariesReached = true;
199  cerr << "m";
200  Vector3d dt;
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());
210  } else {
211  boundariesReached=false;
212  }
213 
214  Eigen::Isometry3d move = Eigen::Isometry3d::Identity();
215  if (boundariesReached){
216  Eigen::Matrix3d mTheta = pose.rotation().inverse() * dtheta;
217  move = mTheta;
218  AngleAxisd aa(mTheta);
219  if (aa.angle()<std::numeric_limits<double>::epsilon()){
220  move.translation() = Vector3d(1., 0., 0.);
221  }
222  } else {
223  double sampled=sampleUniform();
224  if (sampled<pStraight)
225  move=moveStraight;
226  else if (sampled<pStraight+pLeft)
227  move=moveLeft;
228  else
229  move=moveRight;
230  }
231 
232 
233  // select a random move of the robot
234  robot.relativeMove(move);
235  // do a sense
236  cerr << "s";
237  robot.sense();
238  }
239  string fname=outputFilename + ss.str() + ".g2o";
240  //ofstream testStream(fname.c_str());
241  ofstream testStream(outputFilename.c_str());
242  graph.save(testStream);
243 
244 }
void setMinRange(double minRange_)
WorldObject< VertexPointXYZ > WorldObjectTrackXYZ
Command line parsing of argc and argv.
Definition: command_args.h:46
bool addSensor(BaseSensor *sensor)
Definition: simulator.cpp:51
virtual void sense()
Definition: simulator.cpp:61
bool addRobot(BaseRobot *robot)
Definition: simulator.cpp:82
int main(int argc, char **argv)
ParameterSE3Offset * offsetParam2()
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 * offsetParam1()
const PoseType & pose() const
Definition: simulator.h:120
virtual void relativeMove(const PoseType &movement_)
Definition: simulator.h:104
bool addWorldObject(BaseWorldObject *worldObject)
Definition: simulator.cpp:90
ParameterSE3Offset * offsetParam()
VertexType * vertex()
Definition: simulator.h:72
virtual void move(const PoseType &pose_)
Definition: simulator.h:109
ParameterSE3Offset * offsetParam()
#define M_PI
Definition: misc.h:34
Protocol The SLAM executable accepts such as solving the and retrieving or vertices in the graph
Definition: protocol.txt:7
ParameterSE3Offset * offsetParam()
double sampleUniform(double min, double max, std::mt19937 *generator)
Definition: sampler.cpp:35