22 using namespace gtsam;
32 vector<Index> m_cells;
37 LaserFactor(
const vector<Index> &cells) : m_cells(cells) {}
44 virtual double operator()(
const Values &vals)
const{
47 for(
Index i = 0;
i < m_cells.size() - 1;
i++){
48 if(vals.
at(m_cells[
i]) == 1)
53 if(vals.
at(m_cells[m_cells.size() - 1]) == 0)
62 throw runtime_error(
"operator * not implemented");
66 throw runtime_error(
"DecisionTreeFactor toDecisionTreeFactor not implemented");
83 vector<Index> laser_indices_;
88 size_t width()
const {
91 size_t height()
const {
95 class Occupancy :
public Values {
104 OccupancyGrid(
double width,
double height,
double resolution){
105 width_ = width/resolution;
106 height_ = height/resolution;
109 for(
Index i = 0;
i < cellCount();
i++)
114 Occupancy emptyOccupancy(){
116 for(
size_t i = 0;
i < cellCount();
i++)
117 occupancy.insert(pair<Index, size_t>((
Index)
i,0));
124 size_t numStates = 2;
128 vector<double>
table(2);
135 void addLaser(
const Pose2 &
pose,
double range){
139 double step = res_/8.0;
145 for(
double i = 0;
i < range;
i +=
step){
152 key = keyLookup(x,y);
155 if(
i == 0 || key != cells[cells.size()-1])
156 cells.push_back(key);
164 laser_indices_.push_back(factors_.size());
165 push_back(boost::make_shared<LaserFactor>(cells));
170 size_t cellCount()
const {
171 return width_*height_;
175 Index keyLookup(
double x,
double y)
const {
181 x = (double)((
int)
x);
182 y = (double)((
int)
y);
189 size_t index = y*width_ +
x;
190 index = index >= width_*height_ ? -1 : index;
192 return cells_[index];
201 double laserFactorValue(
Index index,
const Occupancy &occupancy)
const{
202 return (*factors_[ laser_indices_[index] ])(occupancy);
206 double operator()(
const Occupancy &occupancy)
const {
212 for(
Index i = 0;
i < laser_indices_.size();
i++){
213 value += laserFactorValue(
i, occupancy);
224 Marginals runMetropolis(
size_t iterations){
225 Occupancy occupancy = emptyOccupancy();
227 size_t size = cellCount();
232 std::uniform_int_distribution<> random_cell(0, size - 1);
237 double Px = (*this)(occupancy);
239 for(
size_t it = 0; it <
marginals.size(); it++)
242 for(
size_t it = 0; it < iterations; it++){
244 Index x = random_cell(rng);
247 occupancy[
x] = 1 - occupancy[
x];
251 double Px_prime = (*this)(occupancy);
255 double a = Px_prime/Px;
265 occupancy[
x] = 1 - occupancy[
x];
270 for(
size_t i = 0;
i <
size;
i++){
271 if(occupancy[
i] == 1)
277 for(
size_t it = 0; it <
size; it++)
286 TEST( OccupancyGrid, Test1) {
292 double resolution = 0.5;
293 OccupancyGrid occupancyGrid(width, height, resolution);
299 occupancyGrid.addPosePrior(0, 0.7);
302 occupancyGrid.addLaser(pose, range);
305 OccupancyGrid::Occupancy occupancy = occupancyGrid.emptyOccupancy();
320 OccupancyGrid::Marginals occupancyMarginals = occupancyGrid.runMetropolis(50000);
Vector3_ operator*(const Double_ &s, const Vector3_ &v)
def step(data, isam, result, truth, currPoseIndex)
static int runAllTests(TestResult &result)
Point2 prior(const Point2 &x)
Prior on a single pose.
graph add(boost::make_shared< UnaryFactor >(1, 0.0, 0.0, unaryNoise))
EIGEN_DEVICE_FUNC const CosReturnType cos() const
const ValueType at(Key j) const
double theta() const
get theta
static const Pose3 pose(Rot3(Vector3(1,-1,-1).asDiagonal()), Point3(0, 0, 0.5))
std::pair< Key, size_t > DiscreteKey
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
#define EXPECT_LONGS_EQUAL(expected, actual)
EIGEN_DEVICE_FUNC const SinReturnType sin() const
Jet< T, N > pow(const Jet< T, N > &f, double g)
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
#define TEST(testGroup, testName)
Marginals marginals(graph, result)