#include <octree_stamped_pa_node.h>
Public Member Functions | |
cOctreeStampedPaNode () | |
default constructor More... | |
virtual octomap_pa_msgs::Config | getConfig (void) |
function for retrieving all current configs More... | |
~cOctreeStampedPaNode () | |
default destructor More... | |
![]() | |
cOctreeBasePaNode (const std::string nodename, const double resolution=0.1, const ros::Duration tf_listener_buffersize=ros::Duration(20)) | |
default constructor More... | |
void | publishOctomap (void) |
function for publishing the octomap More... | |
virtual bool | setConfigDegrading (const octomap_pa_msgs::ConfigDegrading &config) |
function for setting degrading configs (does nothing by default More... | |
bool | setConfigInsertion (const octomap_pa_msgs::ConfigInsertion &config) |
function for setting config for adding pointclouds More... | |
virtual | ~cOctreeBasePaNode () |
default destructor More... | |
![]() | |
cOctreeStampedPaRos (const double resolution) | |
default constructor More... | |
void | degradeOutdatedNodes (void) |
degrading outdated nodes More... | |
ros::Time | getLastInsertionTime (void) const |
function for returning the time the octomap was last updated More... | |
void | setLastInsertionTime (const ros::Time &time) |
function for setting the time the octomap was last updated More... | |
cTimePa | timeFromRos (const ros::Time &time) const |
function for converting from ros::Time to cTimePa More... | |
ros::Time | timeToRos (const cTimePa &time) const |
function for converting from cTimePa to ros::Time More... | |
virtual | ~cOctreeStampedPaRos () |
default destructor More... | |
![]() | |
bool | addCloud (const sensor_msgs::LaserScan &cloud, const cAddCloudParameter ¶ms, const tf::Transform transform=tf::Transform::getIdentity()) |
bool | addCloud (const sensor_msgs::PointCloud &cloud, const cAddCloudParameter ¶ms, const tf::Transform transform=tf::Transform::getIdentity()) |
bool | addCloud (const sensor_msgs::PointCloud2 &cloud, const cAddCloudParameter ¶ms, const tf::Transform transform=tf::Transform::getIdentity()) |
virtual void | clear (void) |
clear local timestamps with octomap More... | |
cOctreeBasePaRos (double resolution) | |
default constructor More... | |
bool | getChildKey (const OctKey ¤t, const int current_level, OctKey &child, const int child_pos) const |
octomap_msgs::OctomapPtr | getOctomap (void) const |
function for getting the binary octomap More... | |
octomap_msgs::OctomapPtr | getOctomapFull (void) const |
function for getting the full octomap More... | |
sensor_msgs::PointCloud2Ptr | getOctomapPcd (const int tree_depth=0, const bool expand=false) const |
function for getting the pointcloud equivalent of the octomap More... | |
sensor_msgs::PointCloud2Ptr | getOctomapPcdFree (const int tree_depth=0, const bool expand=false) const |
similar to getOctomapPcd, but only returning just empty voxels More... | |
ros::Time | getOutputTime (void) const |
function for returning the time of output messages More... | |
bool | getParentKey (const OctKey ¤t, const int current_level, OctKey &parent) const |
geometry_msgs::PointPtr | keyToPoint (const OctKey &key) const |
function for converting from key to point (geometry_msg) More... | |
void | keyToPoint (const OctKey &key, double &x, double &y, double &z) const |
function for converting from key to real coordinates More... | |
OctKey | pointToKey (const geometry_msgs::Point &point) const |
functions for converting from point (geometry_msg) to key More... | |
bool | readFull (const std::string &filename) |
trying to read the given file into the current OcTree More... | |
void | setOutputTime (const ros::Time &time) |
bool | updateTime (const ros::Time &time) |
virtual | ~cOctreeBasePaRos () |
default destructor More... | |
![]() | |
cOcTreeStampedPa (double resolution) | |
Default constructor, sets resolution of leafs. More... | |
cOcTreeStampedPa * | create () const |
virtual std::string | getTreeType () const |
virtual | ~cOcTreeStampedPa (void) |
![]() | |
cOcTreeStampedBasePa (double resolution) | |
Default constructor, sets resolution of leafs. More... | |
cOcTreeStampedBasePa< octomap::OccupancyOcTreeBase, octomap::OcTreeNode > * | create () const |
void | degradeOutdatedNodes (const cTimePa timediff) |
const cTimePa & | getTimestamp (void) const |
void | setTimestamp (const cTimePa timestamp) |
virtual void | updateNodeLogOdds (NodeTypeFull *node, const float &update) const |
virtual | ~cOcTreeStampedBasePa (void) |
Static Public Attributes | |
const static std::string | nodename_ = "octree_stamped_pa_node" |
official node name More... | |
Protected Member Functions | |
virtual void | internal_node_update (void) |
virtual overload for additional updates More... | |
![]() | |
bool | addCloudCallbackSrv (octomap_pa_msgs::AddCloud::Request &req, octomap_pa_msgs::AddCloud::Response &res) |
bool | addCloudTfCallbackSrv (octomap_pa_msgs::AddCloudTf::Request &req, octomap_pa_msgs::AddCloudTf::Response &res) |
void | addLaserCallbackSub (const sensor_msgs::LaserScanConstPtr &msg) |
callback function for receiving a laserscan More... | |
void | addPointcloudCallbackSub (const sensor_msgs::PointCloud2ConstPtr &msg) |
callback function for receiving a pointcloud More... | |
void | addPointcloudOldCallbackSub (const sensor_msgs::PointCloudConstPtr &msg) |
callback function for receiving a pointcloud (old format) More... | |
bool | clearCallbackSrv (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res) |
bool | getCloudCallbackSrv (octomap_pa_msgs::GetCloud::Request &req, octomap_pa_msgs::GetCloud::Response &res) |
bool | getConfigCallbackSrv (octomap_pa_msgs::GetConfig::Request &req, octomap_pa_msgs::GetConfig::Response &res) |
bool | getSizeCallbackSrv (octomap_pa_msgs::GetSize::Request &req, octomap_pa_msgs::GetSize::Response &res) |
bool | loadCallbackSrv (octomap_pa_msgs::FileName::Request &req, octomap_pa_msgs::FileName::Response &res) |
bool | resetCallbackSrv (octomap_pa_msgs::Reset::Request &req, octomap_pa_msgs::Reset::Response &res) |
bool | saveCallbackSrv (octomap_pa_msgs::FileName::Request &req, octomap_pa_msgs::FileName::Response &res) |
bool | setConfigDegradingCallbackSrv (octomap_pa_msgs::SetConfigDegrading::Request &req, octomap_pa_msgs::SetConfigDegrading::Response &res) |
bool | setConfigInsertionCallbackSrv (octomap_pa_msgs::SetConfigInsertion::Request &req, octomap_pa_msgs::SetConfigInsertion::Response &res) |
bool | updateTimeAndGetTF (const std_msgs::Header header, tf::Transform &transform) |
helper function to update/check timestamps & check/retrieve TF More... | |
![]() | |
void | checkDegrading (void) |
helper function for automatic degrading More... | |
![]() | |
bool | addCloud (const PclPointCloudPtr &cloud, const cAddCloudParameter ¶ms, const tf::Transform &transform) |
void | getChildKeySimple (const OctKey ¤t, const int current_level, OctKey &child, const int child_pos) const |
helper function for getChildKey More... | |
void | getOctomapPcdSub (const OctKey &key, const int current_level, const int min_level, PclPointCloud &cloud) const |
helper function for getOctomapPcd... More... | |
void | getParentKeySimple (const OctKey ¤t, const int current_level, OctKey &parent) const |
helper function for getParentKey More... | |
Additional Inherited Members | |
![]() | |
cOctreeStampedPaRosParameter | rosparams_ |
parameters More... | |
![]() | |
cOctreeBasePaRosParameter | rosparams_base_ |
parameters More... | |
![]() | |
cAddCloudParameter | addparams_ |
int | count_cloud_ |
number of inserted pointclouds More... | |
int | count_cloud_old_ |
number of inserted pointclouds (old format) More... | |
int | count_laser_ |
number of inserted laser scans More... | |
ros::NodeHandle | nh_ |
node handler for topic subscription and advertising More... | |
cOctreeBasePaNodeParameter | nodeparams_ |
parameters More... | |
ros::Publisher | pub_cloud_free_ |
puplisher for free voxels as pointcloud More... | |
ros::Publisher | pub_cloud_occupied_ |
puplisher for occupied voxels as pointcloud More... | |
ros::Publisher | pub_octomap_ |
puplisher for the octomap (binary data) More... | |
ros::Publisher | pub_octomap_full_ |
puplisher for the octomap (full data) More... | |
ros::ServiceServer | srv_addcloud_ |
service for adding a new pointcloud to the octomap More... | |
ros::ServiceServer | srv_addcloudtf_ |
service for adding a new pointcloud to the octomap (by passing a tf) More... | |
ros::ServiceServer | srv_clear_ |
service for clearing the octomap More... | |
ros::ServiceServer | srv_getcloud_ |
service for receiving the current octomap as pointcloud More... | |
ros::ServiceServer | srv_getconfig_ |
service for receiving all config of the octomap More... | |
ros::ServiceServer | srv_getsize_ |
service for receiving the current size of the octomap More... | |
ros::ServiceServer | srv_load_ |
service for loading a octomap More... | |
ros::ServiceServer | srv_reset_ |
ros::ServiceServer | srv_save_ |
service for saving the octomap More... | |
ros::ServiceServer | srv_setconfig_degrading_ |
service for setting the degrading config of the octomap More... | |
ros::ServiceServer | srv_setconfig_insertion_ |
service for setting the insertion config of the octomap More... | |
ros::Subscriber | sub_cloud_ |
subscriber for a pointcloud More... | |
ros::Subscriber | sub_cloud_old_ |
subscriber for a pointcloud (old format) More... | |
ros::Subscriber | sub_laser_ |
subscriber for a laserscan More... | |
tf::TransformListener | tf_listener_ |
transformation of different frames More... | |
![]() | |
ros::Time | last_degrading_time_ |
![]() | |
ros::Time | current_output_time_ |
internal variable for storing current output time More... | |
ros::Time | last_insertion_time_ |
internal variable for storing last insertion time More... | |
![]() | |
cTimePa | current_timestamp |
used to set new data (insertion of measurement) to actual time stamp More... | |
![]() | |
static StaticMemberInitializer | StaticMemberInit |
to ensure static initialization (only once) More... | |
Definition at line 60 of file octree_stamped_pa_node.h.
Definition at line 108 of file octree_stamped_pa_node.h.
cOctreeStampedPaNode::cOctreeStampedPaNode | ( | ) |
default constructor
Definition at line 72 of file octree_stamped_pa_node.cpp.
cOctreeStampedPaNode::~cOctreeStampedPaNode | ( | ) |
default destructor
Definition at line 85 of file octree_stamped_pa_node.cpp.
|
virtual |
function for retrieving all current configs
Reimplemented from cOctreeBasePaNode< cOctreeStampedPaRos >.
Definition at line 90 of file octree_stamped_pa_node.cpp.
|
protectedvirtual |
virtual overload for additional updates
Implements cOctreeBasePaNode< cOctreeStampedPaRos >.
Definition at line 109 of file octree_stamped_pa_node.cpp.
|
static |
official node name
Definition at line 120 of file octree_stamped_pa_node.h.