10 int main(
int argc,
char** argv)
13 ros::init(argc, argv,
"grid_map_tutorial_demo");
18 GridMap map({
"elevation",
"normal_x",
"normal_y",
"normal_z"});
21 ROS_INFO(
"Created map with size %f x %f m (%i x %i cells).\n The center of the map is located at (%f, %f) in the %s frame.",
22 map.getLength().x(), map.getLength().y(),
23 map.getSize()(0), map.getSize()(1),
24 map.getPosition().x(), map.getPosition().y(), map.getFrameId().c_str());
34 map.getPosition(*it, position);
35 map.at(
"elevation", *it) = -0.04 + 0.2 * std::sin(3.0 * time.
toSec() + 5.0 * position.y()) * position.x();
36 Eigen::Vector3d normal(-0.2 * std::sin(3.0 * time.
toSec() + 5.0 * position.y()),
37 -position.x() * std::cos(3.0 * time.
toSec() + 5.0 * position.y()), 1.0);
39 map.at(
"normal_x", *it) = normal.x();
40 map.at(
"normal_y", *it) = normal.y();
41 map.at(
"normal_z", *it) = normal.z();
45 map.add(
"noise", 0.015 * Matrix::Random(map.getSize()(0), map.getSize()(1)));
46 map.add(
"elevation_noisy", map.get(
"elevation") + map[
"noise"]);
49 for (
unsigned int i = 0; i < 500; ++i) {
50 Position randomPosition = Position::Random();
51 if (map.isInside(randomPosition))
52 map.atPosition(
"elevation_noisy", randomPosition) = std::numeric_limits<float>::infinity();
56 map.add(
"elevation_filtered", map.get(
"elevation_noisy"));
60 map.getIndex(topLeftCorner, startIndex);
61 ROS_INFO_ONCE(
"Top left corner was limited from (1.0, 0.2) to (%f, %f) and corresponds to index (%i, %i).",
62 topLeftCorner.x(), topLeftCorner.y(), startIndex(0), startIndex(1));
64 Size size = (
Length(1.2, 0.8) / map.getResolution()).cast<int>();
68 map.getPosition(*it, currentPosition);
71 double sumOfWeights = 0.0;
75 if (!map.isValid(*circleIt,
"elevation_noisy"))
continue;
77 map.getPosition(*circleIt, currentPositionInCircle);
80 double distance = (currentPosition - currentPositionInCircle).norm();
81 double weight =
pow(radius - distance, 2);
82 mean += weight * map.at(
"elevation_noisy", *circleIt);
83 sumOfWeights += weight;
86 map.at(
"elevation_filtered", *it) = mean / sumOfWeights;
90 map.add(
"error", (map.get(
"elevation_filtered") - map.get(
"elevation")).cwiseAbs());
93 map.setTimestamp(time.
toNSec());
94 grid_map_msgs::GridMap message;
97 ROS_INFO_THROTTLE(1.0,
"Grid map (timestamp %f) published.", message.info.header.stamp.toSec());
void publish(const boost::shared_ptr< M > &message) const
#define ROS_INFO_ONCE(...)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
static void toMessage(const grid_map::GridMap &gridMap, grid_map_msgs::GridMap &message)
TFSIMD_FORCE_INLINE tfScalar distance(const Vector3 &v) const
Node for comparing different normal filters performances.
int main(int argc, char **argv)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
INLINE Rall1d< T, V, S > pow(const Rall1d< T, V, S > &arg, double m)
#define ROS_INFO_THROTTLE(rate,...)
void boundPositionToRange(Position &position, const Length &mapLength, const Position &mapPosition)
void setFrameId(const std::string &frameId)