Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes
gazebo::OctomapFromGazeboWorld Class Reference

Octomap plugin for Gazebo. More...

#include <gazebo_octomap_plugin.h>

List of all members.

Public Member Functions

 OctomapFromGazeboWorld ()
virtual ~OctomapFromGazeboWorld ()

Protected Member Functions

bool CheckIfInterest (const ignition::math::Vector3d &central_point, gazebo::physics::RayShapePtr ray, const double leaf_size)
void CreateOctomap (const rotors_comm::Octomap::Request &msg)
 Creates octomap by floodfilling freespace.
void FloodFill (const ignition::math::Vector3d &seed_point, const ignition::math::Vector3d &bounding_box_origin, const ignition::math::Vector3d &bounding_box_lengths, const double leaf_size)
void Load (physics::WorldPtr _parent, sdf::ElementPtr _sdf)
 Load the plugin.

Private Member Functions

bool ServiceCallback (rotors_comm::Octomap::Request &req, rotors_comm::Octomap::Response &res)

Private Attributes

ros::NodeHandle node_handle_
octomap::OcTreeoctomap_
ros::Publisher octomap_publisher_
ros::ServiceServer srv_
physics::WorldPtr world_

Detailed Description

Octomap plugin for Gazebo.

This plugin is dependent on ROS, and is not built if NO_ROS=TRUE is provided to CMakeLists.txt. The PX4/Firmware build does not build this file.

Definition at line 43 of file gazebo_octomap_plugin.h.


Constructor & Destructor Documentation

Definition at line 45 of file gazebo_octomap_plugin.h.

Definition at line 30 of file gazebo_octomap_plugin.cpp.


Member Function Documentation

bool gazebo::OctomapFromGazeboWorld::CheckIfInterest ( const ignition::math::Vector3d &  central_point,
gazebo::physics::RayShapePtr  ray,
const double  leaf_size 
) [protected]

Definition at line 135 of file gazebo_octomap_plugin.cpp.

void gazebo::OctomapFromGazeboWorld::CreateOctomap ( const rotors_comm::Octomap::Request &  msg) [protected]

Creates octomap by floodfilling freespace.

Creates an octomap of the environment in 3 steps:

  1. Casts rays along the central X,Y and Z axis of each cell. Marks any cell where a ray intersects a mesh as occupied
  2. Floodfills the area from the top and bottom marking all connected space that has not been set to occupied as free.
  3. Labels all remaining unknown space as occupied.

Can give incorrect results in the following situations:

  1. The top central cell or bottom central cell are either occupied or completely enclosed by occupied cells.
  2. A completely enclosed hollow space will be marked as occupied.
  3. Cells containing a mesh that does not intersect its central axes will be marked as unoccupied

Definition at line 172 of file gazebo_octomap_plugin.cpp.

void gazebo::OctomapFromGazeboWorld::FloodFill ( const ignition::math::Vector3d &  seed_point,
const ignition::math::Vector3d &  bounding_box_origin,
const ignition::math::Vector3d &  bounding_box_lengths,
const double  leaf_size 
) [protected]

Definition at line 99 of file gazebo_octomap_plugin.cpp.

void gazebo::OctomapFromGazeboWorld::Load ( physics::WorldPtr  _parent,
sdf::ElementPtr  _sdf 
) [protected]

Load the plugin.

Parameters:
[in]_parentPointer to the world that loaded this plugin.
[in]_sdfSDF element that describes the plugin.

Definition at line 35 of file gazebo_octomap_plugin.cpp.

bool gazebo::OctomapFromGazeboWorld::ServiceCallback ( rotors_comm::Octomap::Request &  req,
rotors_comm::Octomap::Response &  res 
) [private]

Definition at line 57 of file gazebo_octomap_plugin.cpp.


Member Data Documentation

Definition at line 85 of file gazebo_octomap_plugin.h.

Definition at line 87 of file gazebo_octomap_plugin.h.

Definition at line 88 of file gazebo_octomap_plugin.h.

Definition at line 86 of file gazebo_octomap_plugin.h.

physics::WorldPtr gazebo::OctomapFromGazeboWorld::world_ [private]

Definition at line 84 of file gazebo_octomap_plugin.h.


The documentation for this class was generated from the following files:


rotors_gazebo_plugins
Author(s): Fadri Furrer, Michael Burri, Mina Kamel, Janosch Nikolic, Markus Achtelik
autogenerated on Thu Apr 18 2019 02:43:43