Skip to content

Commit

Permalink
Imported upstream version '0.6.8' of 'upstream'
Browse files Browse the repository at this point in the history
  • Loading branch information
wxmerkt committed Mar 24, 2024
1 parent 52c33b1 commit a38148c
Show file tree
Hide file tree
Showing 11 changed files with 60 additions and 46 deletions.
24 changes: 5 additions & 19 deletions .github/workflows/industrial_ci_action.yml
Original file line number Diff line number Diff line change
@@ -1,34 +1,20 @@
# This config uses industrial_ci (https://github.com/ros-industrial/industrial_ci.git).
# For troubleshooting, see readme (https://github.com/ros-industrial/industrial_ci/blob/master/README.rst)

name: CI

# This determines when this workflow is run
on: [push, pull_request] # on all pushes and PRs
on: [push, pull_request]

jobs:
CI:
strategy:
matrix:
env:
- {ROS_DISTRO: kinetic}
- {ROS_DISTRO: kinetic, PRERELEASE: true}
- {ROS_DISTRO: melodic}
- {ROS_DISTRO: melodic, PRERELEASE: true}
#- {ROS_DISTRO: melodic}
#- {ROS_DISTRO: melodic, PRERELEASE: true}
- {ROS_DISTRO: noetic}
- {ROS_DISTRO: noetic, PRERELEASE: true}
- {ROS_DISTRO: noetic, OS_NAME: debian, OS_CODE_NAME: buster}
#- {ROS_DISTRO: noetic, OS_NAME: debian, OS_CODE_NAME: buster}
env:
CCACHE_DIR: /github/home/.ccache # Enable ccache
PARALLEL_BUILDS: 4
runs-on: ubuntu-latest
steps:
- uses: actions/checkout@v2
# This step will fetch/store the directory used by ccache before/after the ci run
- uses: actions/cache@v2
with:
path: ${{ env.CCACHE_DIR }}
key: ccache-${{ matrix.env.ROS_DISTRO }}-${{ matrix.env.ROS_REPO }}
# Run industrial_ci
- uses: actions/checkout@v3
- uses: 'ros-industrial/industrial_ci@master'
env: ${{ matrix.env }}
4 changes: 3 additions & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -3,4 +3,6 @@ octomap_mapping ![CI](https://github.com/OctoMap/octomap_mapping/workflows/CI/ba

ROS stack for mapping with OctoMap, contains the `octomap_server` package.

The main branch for ROS Kinetic and newer is `kinetic-devel`.
The main branch for ROS1 Kinetic, Melodic, and Noetic is `kinetic-devel`.

The main branch for ROS2 Foxy and newer is `ros2`.
3 changes: 3 additions & 0 deletions octomap_mapping/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@
Changelog for package octomap_mapping
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

0.6.8 (2024-03-24)
------------------

0.6.7 (2021-12-24)
------------------
* Address warnings on Noetic (`#81 <https://github.com/octomap/octomap_mapping/issues/81>`_)
Expand Down
2 changes: 1 addition & 1 deletion octomap_mapping/package.xml
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<package>
<name>octomap_mapping</name>
<version>0.6.7</version>
<version>0.6.8</version>
<description>
Mapping tools to be used with the <a href="https://octomap.github.io/">OctoMap library</a>, implementing a 3D occupancy grid mapping.
</description>
Expand Down
11 changes: 11 additions & 0 deletions octomap_server/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,17 @@
Changelog for package octomap_server
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

0.6.8 (2024-03-24)
------------------
* Change frame id "/map" to "map" to prevent RViz visualization warnings in ROS Noetic caused by tf (`#124 <https://github.com/octomap/octomap_mapping/issues/124>`_
* Initialize quaternion to avoid RViz warning (`#112 <https://github.com/octomap/octomap_mapping/issues/112>`_)
* Update for PCL deprecated and removed API (`#118 <https://github.com/octomap/octomap_mapping/issues/118>`_)
* Update pluginlib headers (`#114 <https://github.com/OctoMap/octomap_mapping/issues/114>`_)
* Update boost::placeholders (`#105 <https://github.com/octomap/octomap_mapping/issues/105>`_)
* Fix publishing of projected map on reset (`#92 <https://github.com/octomap/octomap_mapping/issues/92>`_)
* Add a min range parameter (`#100 <https://github.com/octomap/octomap_mapping/issues/100>`_)
* Contributors: Lovro Markovic, Lucas Walter, Wolfgang Merkt, Zhefan-Xu, yuri-r

0.6.7 (2021-12-24)
------------------
* Address warnings on Noetic (`#81 <https://github.com/octomap/octomap_mapping/issues/81>`_)
Expand Down
1 change: 1 addition & 0 deletions octomap_server/cfg/OctomapServer.cfg
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@ gen.add("pointcloud_max_z", double_t, 0, "Maximum height of points to consider f
gen.add("occupancy_min_z", double_t, 0, "Minimum height of occupied cells to consider in the final map", -100, -100, 100)
gen.add("occupancy_max_z", double_t, 0, "Maximum height of occupied cells to consider in the final map", 100, -100, 100)
gen.add("sensor_model_max_range", double_t, 0, "Sensor maximum range", -1.0, -1.0, 100)
gen.add("sensor_model_min_range", double_t, 0, "Sensor minimum range", -1.0, -1.0, 100)
gen.add("sensor_model_hit", double_t, 0, "Probabilities for hits in the sensor model when dynamically building a map", 0.7, 0.5, 1.0)
gen.add("sensor_model_miss", double_t, 0, "Probabilities for misses in the sensor model when dynamically building a map", 0.4, 0.0, 0.5)
gen.add("sensor_model_min", double_t, 0, "Minimum probability for clamping when dynamically building a map", 0.12, 0.0, 1.0)
Expand Down
2 changes: 2 additions & 0 deletions octomap_server/include/octomap_server/OctomapServer.h
Original file line number Diff line number Diff line change
Expand Up @@ -128,6 +128,7 @@ class OctomapServer {
void reconfigureCallback(octomap_server::OctomapServerConfig& config, uint32_t level);
void publishBinaryOctoMap(const ros::Time& rostime = ros::Time::now()) const;
void publishFullOctoMap(const ros::Time& rostime = ros::Time::now()) const;
void publishProjected2DMap(const ros::Time& rostime = ros::Time::now());
virtual void publishAll(const ros::Time& rostime = ros::Time::now());

/**
Expand Down Expand Up @@ -218,6 +219,7 @@ class OctomapServer {
octomap::OcTreeKey m_updateBBXMin;
octomap::OcTreeKey m_updateBBXMax;

double m_minRange;
double m_maxRange;
std::string m_worldFrameId; // the map frame
std::string m_baseFrameId; // base of the robot for ground plane filtering
Expand Down
2 changes: 1 addition & 1 deletion octomap_server/package.xml
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<package format="3">
<name>octomap_server</name>
<version>0.6.7</version>
<version>0.6.8</version>
<description>
octomap_server loads a 3D map (as Octree-based OctoMap) and distributes it to other nodes in a compact binary format. It also allows to incrementally build 3D OctoMaps, and provides map saving in the node octomap_saver.
</description>
Expand Down
53 changes: 31 additions & 22 deletions octomap_server/src/OctomapServer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,8 @@ OctomapServer::OctomapServer(const ros::NodeHandle private_nh_, const ros::NodeH
m_reconfigureServer(m_config_mutex, private_nh_),
m_octree(NULL),
m_maxRange(-1.0),
m_worldFrameId("/map"), m_baseFrameId("base_footprint"),
m_minRange(-1.0),
m_worldFrameId("map"), m_baseFrameId("base_footprint"),
m_useHeightMap(true),
m_useColoredMap(false),
m_colorFactor(0.8),
Expand Down Expand Up @@ -100,6 +101,7 @@ OctomapServer::OctomapServer(const ros::NodeHandle private_nh_, const ros::NodeH
m_nh_private.param("ground_filter/plane_distance", m_groundFilterPlaneDistance, m_groundFilterPlaneDistance);

m_nh_private.param("sensor_model/max_range", m_maxRange, m_maxRange);
m_nh_private.param("sensor_model/min_range", m_minRange, m_minRange);

m_nh_private.param("resolution", m_res, m_res);
m_nh_private.param("sensor_model/hit", probHit, 0.7);
Expand Down Expand Up @@ -174,15 +176,15 @@ OctomapServer::OctomapServer(const ros::NodeHandle private_nh_, const ros::NodeH

m_pointCloudSub = new message_filters::Subscriber<sensor_msgs::PointCloud2> (m_nh, "cloud_in", 5);
m_tfPointCloudSub = new tf::MessageFilter<sensor_msgs::PointCloud2> (*m_pointCloudSub, m_tfListener, m_worldFrameId, 5);
m_tfPointCloudSub->registerCallback(boost::bind(&OctomapServer::insertCloudCallback, this, _1));
m_tfPointCloudSub->registerCallback(boost::bind(&OctomapServer::insertCloudCallback, this, boost::placeholders::_1));

m_octomapBinaryService = m_nh.advertiseService("octomap_binary", &OctomapServer::octomapBinarySrv, this);
m_octomapFullService = m_nh.advertiseService("octomap_full", &OctomapServer::octomapFullSrv, this);
m_clearBBXService = m_nh_private.advertiseService("clear_bbx", &OctomapServer::clearBBXSrv, this);
m_resetService = m_nh_private.advertiseService("reset", &OctomapServer::resetSrv, this);

dynamic_reconfigure::Server<OctomapServerConfig>::CallbackType f;
f = boost::bind(&OctomapServer::reconfigureCallback, this, _1, _2);
f = boost::bind(&OctomapServer::reconfigureCallback, this, boost::placeholders::_1, boost::placeholders::_2);
m_reconfigureServer.setCallback(f);
}

Expand Down Expand Up @@ -370,6 +372,9 @@ void OctomapServer::insertScan(const tf::Point& sensorOriginTf, const PCLPointCl
// insert ground points only as free:
for (PCLPointCloud::const_iterator it = ground.begin(); it != ground.end(); ++it){
point3d point(it->x, it->y, it->z);

if ((m_minRange > 0) && (point - sensorOrigin).norm() < m_minRange) continue;

// maxrange check
if ((m_maxRange > 0.0) && ((point - sensorOrigin).norm() > m_maxRange) ) {
point = sensorOrigin + (point - sensorOrigin).normalized() * m_maxRange;
Expand All @@ -392,6 +397,9 @@ void OctomapServer::insertScan(const tf::Point& sensorOriginTf, const PCLPointCl
// all other points: free on ray, occupied on endpoint:
for (PCLPointCloud::const_iterator it = nonground.begin(); it != nonground.end(); ++it){
point3d point(it->x, it->y, it->z);

if ((m_minRange > 0) && (point - sensorOrigin).norm() < m_minRange) continue;

// maxrange check
if ((m_maxRange < 0.0) || ((point - sensorOrigin).norm() <= m_maxRange) ) {

Expand Down Expand Up @@ -478,7 +486,13 @@ void OctomapServer::insertScan(const tf::Point& sensorOriginTf, const PCLPointCl
#endif
}


void OctomapServer::publishProjected2DMap(const ros::Time& rostime) {
m_publish2DMap = (m_latchedTopics || m_mapPub.getNumSubscribers() > 0);
if (m_publish2DMap) {
m_gridmap.header.stamp = rostime;
m_mapPub.publish(m_gridmap);
}
}

void OctomapServer::publishAll(const ros::Time& rostime){
ros::WallTime startTime = ros::WallTime::now();
Expand All @@ -494,7 +508,6 @@ void OctomapServer::publishAll(const ros::Time& rostime){
bool publishPointCloud = (m_latchedTopics || m_pointCloudPub.getNumSubscribers() > 0);
bool publishBinaryMap = (m_latchedTopics || m_binaryMapPub.getNumSubscribers() > 0);
bool publishFullMap = (m_latchedTopics || m_fullMapPub.getNumSubscribers() > 0);
m_publish2DMap = (m_latchedTopics || m_mapPub.getNumSubscribers() > 0);

// init markers for free space:
visualization_msgs::MarkerArray freeNodesVis;
Expand Down Expand Up @@ -639,6 +652,10 @@ void OctomapServer::publishAll(const ros::Time& rostime){
occupiedNodesVis.markers[i].scale.x = size;
occupiedNodesVis.markers[i].scale.y = size;
occupiedNodesVis.markers[i].scale.z = size;
occupiedNodesVis.markers[i].pose.orientation.x=0;
occupiedNodesVis.markers[i].pose.orientation.y=0;
occupiedNodesVis.markers[i].pose.orientation.z=0;
occupiedNodesVis.markers[i].pose.orientation.w=1;
if (!m_useColoredMap)
occupiedNodesVis.markers[i].color = m_color;

Expand Down Expand Up @@ -697,10 +714,8 @@ void OctomapServer::publishAll(const ros::Time& rostime){

double total_elapsed = (ros::WallTime::now() - startTime).toSec();
ROS_DEBUG("Map publishing in OctomapServer took %f sec", total_elapsed);

}


bool OctomapServer::octomapBinarySrv(OctomapSrv::Request &req,
OctomapSrv::Response &res)
{
Expand Down Expand Up @@ -763,26 +778,25 @@ bool OctomapServer::resetSrv(std_srvs::Empty::Request& req, std_srvs::Empty::Res
m_gridmap.info.origin.position.y = 0.0;

ROS_INFO("Cleared octomap");
publishAll(rostime);
publishAll(rostime); // Note: This will return as the octree is empty

publishProjected2DMap(rostime);

publishBinaryOctoMap(rostime);
for (unsigned i= 0; i < occupiedNodesVis.markers.size(); ++i){

for (std::size_t i = 0; i < occupiedNodesVis.markers.size(); ++i){
occupiedNodesVis.markers[i].header.frame_id = m_worldFrameId;
occupiedNodesVis.markers[i].header.stamp = rostime;
occupiedNodesVis.markers[i].ns = "map";
occupiedNodesVis.markers[i].id = i;
occupiedNodesVis.markers[i].type = visualization_msgs::Marker::CUBE_LIST;
occupiedNodesVis.markers[i].action = visualization_msgs::Marker::DELETE;
}

m_markerPub.publish(occupiedNodesVis);

visualization_msgs::MarkerArray freeNodesVis;
freeNodesVis.markers.resize(m_treeDepth +1);

for (unsigned i= 0; i < freeNodesVis.markers.size(); ++i){

for (std::size_t i = 0; i < freeNodesVis.markers.size(); ++i){
freeNodesVis.markers[i].header.frame_id = m_worldFrameId;
freeNodesVis.markers[i].header.stamp = rostime;
freeNodesVis.markers[i].ns = "map";
Expand Down Expand Up @@ -914,7 +928,7 @@ void OctomapServer::filterGroundPlane(const PCLPointCloud& pc, PCLPointCloud& gr
second_pass.setInputCloud(pc.makeShared());
second_pass.filter(ground);

second_pass.setFilterLimitsNegative (true);
second_pass.setNegative (true);
second_pass.filter(nonground);
}

Expand Down Expand Up @@ -1041,41 +1055,34 @@ void OctomapServer::handlePreNodeTraversal(const ros::Time& rostime){
}

void OctomapServer::handlePostNodeTraversal(const ros::Time& rostime){

if (m_publish2DMap)
m_mapPub.publish(m_gridmap);
publishProjected2DMap(rostime);
}

void OctomapServer::handleOccupiedNode(const OcTreeT::iterator& it){

if (m_publish2DMap && m_projectCompleteMap){
update2DMap(it, true);
}
}

void OctomapServer::handleFreeNode(const OcTreeT::iterator& it){

if (m_publish2DMap && m_projectCompleteMap){
update2DMap(it, false);
}
}

void OctomapServer::handleOccupiedNodeInBBX(const OcTreeT::iterator& it){

if (m_publish2DMap && !m_projectCompleteMap){
update2DMap(it, true);
}
}

void OctomapServer::handleFreeNodeInBBX(const OcTreeT::iterator& it){

if (m_publish2DMap && !m_projectCompleteMap){
update2DMap(it, false);
}
}

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

// update 2D map (occupied always overrides):

if (it.getDepth() == m_maxTreeDepth){
Expand Down Expand Up @@ -1152,6 +1159,8 @@ void OctomapServer::reconfigureCallback(octomap_server::OctomapServerConfig& con
config.ground_filter_plane_distance = m_groundFilterPlaneDistance;
if(!is_equal(m_maxRange, -1.0))
config.sensor_model_max_range = m_maxRange;
if(!is_equal(m_minRange, -1.0))
config.sensor_model_min_range = m_minRange;
if(!is_equal(m_octree->getProbHit(), 0.7))
config.sensor_model_hit = m_octree->getProbHit();
if(!is_equal(m_octree->getProbMiss(), 0.4))
Expand Down
2 changes: 1 addition & 1 deletion octomap_server/src/octomap_server_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@

#include <ros/ros.h>
#include <octomap_server/OctomapServer.h>
#include <pluginlib/class_list_macros.h>
#include <pluginlib/class_list_macros.hpp>
#include <nodelet/nodelet.h>


Expand Down
2 changes: 1 addition & 1 deletion octomap_server/src/octomap_server_static.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ using namespace octomap;
class OctomapServerStatic{
public:
OctomapServerStatic(const std::string& filename)
: m_octree(NULL), m_worldFrameId("/map")
: m_octree(NULL), m_worldFrameId("map")
{

ros::NodeHandle private_nh("~");
Expand Down

0 comments on commit a38148c

Please sign in to comment.