Octomap plugin for Gazebo. More...
#include <gazebo_octomap_plugin.h>
Public Member Functions | |
OctomapFromGazeboWorld () | |
virtual | ~OctomapFromGazeboWorld () |
Protected Member Functions | |
bool | CheckIfInterest (const ignition::math::Vector3d ¢ral_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::OcTree * | octomap_ |
ros::Publisher | octomap_publisher_ |
ros::ServiceServer | srv_ |
physics::WorldPtr | world_ |
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.
Definition at line 45 of file gazebo_octomap_plugin.h.
gazebo::OctomapFromGazeboWorld::~OctomapFromGazeboWorld | ( | ) | [virtual] |
Definition at line 30 of file gazebo_octomap_plugin.cpp.
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:
Can give incorrect results in the following situations:
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.
[in] | _parent | Pointer to the world that loaded this plugin. |
[in] | _sdf | SDF 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.
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.