Class OctomapServer

Inheritance Relationships

Base Type

  • public rclcpp::Node

Derived Types

Class Documentation

class OctomapServer : public rclcpp::Node

Subclassed by octomap_server::OctomapServerMultilayer, octomap_server::TrackingOctomapServer

Public Types

using PCLPoint = pcl::PointXYZ
using PCLPointCloud = pcl::PointCloud<pcl::PointXYZ>
using OcTreeT = octomap::OcTree
using OctomapSrv = octomap_msgs::srv::GetOctomap
using BBoxSrv = octomap_msgs::srv::BoundingBoxQuery
using ResetSrv = std_srvs::srv::Empty

Public Functions

explicit OctomapServer(const rclcpp::NodeOptions &node_options)
virtual bool onOctomapBinarySrv(const std::shared_ptr<OctomapSrv::Request> req, const std::shared_ptr<OctomapSrv::Response> res)
virtual bool onOctomapFullSrv(const std::shared_ptr<OctomapSrv::Request> req, const std::shared_ptr<OctomapSrv::Response> res)
bool clearBBoxSrv(const std::shared_ptr<BBoxSrv::Request> req, const std::shared_ptr<BBoxSrv::Response> resp)
bool resetSrv(const std::shared_ptr<ResetSrv::Request> req, const std::shared_ptr<ResetSrv::Response> resp)
virtual void insertCloudCallback(const PointCloud2::ConstSharedPtr cloud)
virtual bool openFile(const std::string &filename)

Protected Functions

inline bool isInUpdateBBX(const OcTreeT::iterator &it) const

Test if key is within update area of map (2D, ignores height)

rcl_interfaces::msg::SetParametersResult onParameter(const std::vector<rclcpp::Parameter> &parameters)
void publishBinaryOctoMap(const rclcpp::Time &rostime) const
void publishFullOctoMap(const rclcpp::Time &rostime) const
virtual void publishAll(const rclcpp::Time &rostime)
virtual void insertScan(const tf2::Vector3 &sensor_origin, const PCLPointCloud &ground, const PCLPointCloud &nonground)

update occupancy map with a scan labeled as ground and nonground. The scans should be in the global map frame.

Parameters:
  • sensor_origin – origin of the measurements for raycasting

  • ground – scan endpoints on the ground plane (only clear space)

  • nonground – all other endpoints (clear up to occupied endpoint)

void filterGroundPlane(const PCLPointCloud &pc, PCLPointCloud &ground, PCLPointCloud &nonground) const

label the input cloud “pc” into ground and nonground. Should be in the robot’s fixed frame (not world!)

bool isSpeckleNode(const octomap::OcTreeKey &key) const

Find speckle nodes (single occupied voxels with no neighbors). Only works on lowest resolution!

Parameters:

key

Returns:

virtual void handlePreNodeTraversal(const rclcpp::Time &rostime)

hook that is called before traversing all nodes

inline virtual void handleNode([[maybe_unused]] const OcTreeT::iterator &it)

hook that is called when traversing all nodes of the updated Octree (does nothing here)

inline virtual void handleNodeInBBX([[maybe_unused]] const OcTreeT::iterator &it)

hook that is called when traversing all nodes of the updated Octree in the updated area (does nothing here)

virtual void handleOccupiedNode(const OcTreeT::iterator &it)

hook that is called when traversing occupied nodes of the updated Octree

virtual void handleOccupiedNodeInBBX(const OcTreeT::iterator &it)

hook that is called when traversing occupied nodes in the updated area (updates 2D map projection here)

virtual void handleFreeNode(const OcTreeT::iterator &it)

hook that is called when traversing free nodes of the updated Octree

virtual void handleFreeNodeInBBX(const OcTreeT::iterator &it)

hook that is called when traversing free nodes in the updated area (updates 2D map projection here)

virtual void handlePostNodeTraversal(const rclcpp::Time &rostime)

hook that is called after traversing all nodes

virtual void update2DMap(const OcTreeT::iterator &it, bool occupied)

updates the downprojected 2D map as either occupied or free

inline size_t mapIdx(const int i, const int j) const
inline size_t mapIdx(const octomap::OcTreeKey &key) const
void adjustMapData(OccupancyGrid &map, const MapMetaData &old_map_info) const

Adjust data of map due to a change in its info properties (origin or size, resolution needs to stay fixed). map already contains the new map info, but the data is stored according to old_map_info.

inline bool mapChanged(const MapMetaData &old_map_info, const MapMetaData &new_map_info)

Protected Attributes

OnSetParametersCallbackHandle::SharedPtr set_param_res_
rclcpp::Publisher<MarkerArray>::SharedPtr marker_pub_
rclcpp::Publisher<Octomap>::SharedPtr binary_map_pub_
rclcpp::Publisher<Octomap>::SharedPtr full_map_pub_
rclcpp::Publisher<PointCloud2>::SharedPtr point_cloud_pub_
rclcpp::Publisher<OccupancyGrid>::SharedPtr map_pub_
rclcpp::Publisher<MarkerArray>::SharedPtr fmarker_pub_
message_filters::Subscriber<PointCloud2> point_cloud_sub_
std::shared_ptr<tf2_ros::MessageFilter<PointCloud2>> tf_point_cloud_sub_
rclcpp::Service<OctomapSrv>::SharedPtr octomap_binary_srv_
rclcpp::Service<OctomapSrv>::SharedPtr octomap_full_srv_
rclcpp::Service<BBoxSrv>::SharedPtr clear_bbox_srv_
rclcpp::Service<ResetSrv>::SharedPtr reset_srv_
std::shared_ptr<tf2_ros::Buffer> tf2_buffer_
std::shared_ptr<tf2_ros::TransformListener> tf2_listener_
std::unique_ptr<OcTreeT> octree_
octomap::KeyRay key_ray_
octomap::OcTreeKey update_bbox_min_
octomap::OcTreeKey update_bbox_max_
double max_range_
std::string world_frame_id_
std::string base_frame_id_
bool use_height_map_
ColorRGBA color_
ColorRGBA color_free_
double color_factor_
bool latched_topics_
bool publish_free_space_
double res_
size_t tree_depth_
size_t max_tree_depth_
double point_cloud_min_x_
double point_cloud_max_x_
double point_cloud_min_y_
double point_cloud_max_y_
double point_cloud_min_z_
double point_cloud_max_z_
double occupancy_min_z_
double occupancy_max_z_
double min_x_size_
double min_y_size_
bool filter_speckles_
bool filter_ground_plane_
double ground_filter_distance_
double ground_filter_angle_
double ground_filter_plane_distance_
bool compress_map_
bool init_config_
bool incremental_2D_projection_
OccupancyGrid gridmap_
bool publish_2d_map_
bool map_origin_changed
octomap::OcTreeKey padded_min_key_
unsigned multires_2d_scale_
bool project_complete_map_
bool use_colored_map_

Protected Static Functions

static inline void updateMinKey(const octomap::OcTreeKey &in, octomap::OcTreeKey &min)
static inline void updateMaxKey(const octomap::OcTreeKey &in, octomap::OcTreeKey &max)
static ColorRGBA heightMapColor(double h)