ray_tracer.h File Reference

#include <occupancy_grid_utils/impl/ray_trace_iterator.h>
#include <occupancy_grid_utils/coordinate_conversions.h>
#include <ros/assert.h>
#include <boost/iterator/iterator_facade.hpp>
#include <string>
#include <vector>
#include <ostream>
#include "ros/serialization.h"
#include "ros/builtin_message_traits.h"
#include "ros/message_operations.h"
#include "ros/message.h"
#include "ros/time.h"
#include "std_msgs/Header.h"
#include "geometry_msgs/Pose.h"
#include "geometry_msgs/Point32.h"
#include "nav_msgs/OccupancyGrid.h"
#include <boost/optional.hpp>
Include dependency graph for ray_tracer.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Namespaces

namespace  occupancy_grid_utils

Typedefs

typedef std::pair
< RayTraceIterator,
RayTraceIterator > 
occupancy_grid_utils::RayTraceIterRange

Functions

void occupancy_grid_utils::addCloud (OverlayClouds *overlay, LocalizedCloud::ConstPtr cloud)
 Raytrace a cloud onto grid in overlay.
void occupancy_grid_utils::addKnownFreePoint (OverlayClouds *overlay, const geometry_msgs::Point &p, double r)
 Assert that a square centered at this point with side 2*r contains no obstacles.
OverlayClouds occupancy_grid_utils::createCloudOverlay (const nav_msgs::OccupancyGrid &grid, const std::string &frame_id, double occupancy_threshold=DEFAULT_OCCUPANCY_THRESHOLD, double max_distance=DEFAULT_MAX_DISTANCE, double min_pass_through=DEFAULT_MIN_PASS_THROUGH)
 Create a cloud overlay object to which clouds can then be added The returned (ros message) object should only be accessed using the api below.
nav_msgs::OccupancyGrid::Ptr occupancy_grid_utils::getGrid (const OverlayClouds &overlay)
 Get the current grid. It's fine to modify the returned object.
nav_msgs::MapMetaData occupancy_grid_utils::gridInfo (const OverlayClouds &overlay)
RayTraceIterRange occupancy_grid_utils::rayTrace (const nav_msgs::MapMetaData &info, const geometry_msgs::Point &p1, const geometry_msgs::Point &p2, bool project_target_onto_grid=false, bool project_source_onto_grid=false)
 Returns an iterator range over the cells on the line segment between two points (inclusive).
void occupancy_grid_utils::removeCloud (OverlayClouds *overlay, LocalizedCloud::ConstPtr cloud)
 Effectively subtract a cloud (which was presumably previously added), by subtracting rather than adding counts, in overlay.
void occupancy_grid_utils::resetCounts (OverlayClouds *overlay)

Variables

const double occupancy_grid_utils::DEFAULT_MAX_DISTANCE = 10.0
 Default max_distance for OverlayClouds.
const double occupancy_grid_utils::DEFAULT_MIN_PASS_THROUGH = 2
 Default min_pass_through for OverlayClouds.
const double occupancy_grid_utils::DEFAULT_OCCUPANCY_THRESHOLD = 0.1
 Default occupancy threshold for OverlayClouds.
 All Classes Namespaces Files Functions Variables Typedefs Friends


occupancy_grid_utils
Author(s): Bhaskara Marthi
autogenerated on Fri Jan 11 10:07:09 2013