Skip to content

Commit f92b293

Browse files
committed
Switched to the new octomap_ros package
1 parent dd04bf6 commit f92b293

File tree

4 files changed

+12
-12
lines changed

4 files changed

+12
-12
lines changed

octocostmap/include/octocostmap/costmap_3d.h

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -39,7 +39,7 @@
3939
#include <tf/transform_listener.h>
4040
#include <tf/transform_datatypes.h>
4141
#include <octomap/octomap.h>
42-
#include <octomap_server/OctomapBinary.h>
42+
#include <octomap_ros/OctomapBinary.h>
4343
#include <geometry_msgs/PointStamped.h>
4444
#include <boost/thread/shared_mutex.hpp>
4545
#include <vector>
@@ -49,7 +49,7 @@ namespace octocostmap {
4949
public:
5050
Costmap3D(const std::string &name, tf::TransformListener &tfl);
5151

52-
void octomapCallback(const octomap_server::OctomapBinary::ConstPtr& map);
52+
void octomapCallback(const octomap_ros::OctomapBinary::ConstPtr& map);
5353

5454
bool checkCollisionVolume(const std::vector<tf::Point > &collision_volume);
5555

octocostmap/manifest.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -9,7 +9,7 @@
99
<review status="unreviewed" notes=""/>
1010
<url>http://ros.org/wiki/octocostmap</url>
1111
<depend package="roscpp"/>
12-
<depend package="octomap_server"/>
12+
<depend package="octomap_ros"/>
1313
<depend package="sensor_msgs"/>
1414
<depend package="pcl_ros" />
1515
<depend package="tf" />

octocostmap/src/costmap_3d.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -33,22 +33,22 @@
3333
*********************************************************************/
3434

3535
#include <octocostmap/costmap_3d.h>
36-
#include <octomap_server/octomap_server.h>
36+
#include <octomap_ros/conversions.h>
3737
#include <boost/foreach.hpp>
3838
#include <pcl_ros/point_cloud.h>
3939
#include <pcl/point_types.h>
4040

4141
namespace octocostmap {
4242
Costmap3D::Costmap3D(const std::string &name, tf::TransformListener &tfl):
4343
name_(name), map_frame_("map"), tfl_(tfl), nh_(), priv_nh_("~/" + name_), octree_(0.5) {
44-
octomap_sub_ = nh_.subscribe<octomap_server::OctomapBinary>("octomap", 1, boost::bind(&Costmap3D::octomapCallback, this, _1));
44+
octomap_sub_ = nh_.subscribe<octomap_ros::OctomapBinary>("octomap", 1, boost::bind(&Costmap3D::octomapCallback, this, _1));
4545
collision_volume_pub_ = nh_.advertise<pcl::PointCloud<pcl::PointXYZ> >("collison_volume_cloud", 1);
4646
}
4747

48-
void Costmap3D::octomapCallback(const octomap_server::OctomapBinary::ConstPtr& map) {
48+
void Costmap3D::octomapCallback(const octomap_ros::OctomapBinary::ConstPtr& map) {
4949
bool locked = octree_lock_.try_lock();
5050
if (locked) {
51-
octomap_server::octomapMsgToMap(*map, octree_);
51+
octomap::octomapMsgToMap(*map, octree_);
5252
map_frame_= map->header.frame_id;
5353
octree_lock_.unlock();
5454
}

octocostmap/src/octocostmap.cpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -33,8 +33,8 @@
3333
*********************************************************************/
3434

3535
#include <octocostmap/octocostmap.h>
36-
#include <octomap_server/octomap_server.h>
37-
#include <octomap_server/OctomapBinary.h>
36+
#include <octomap_ros/conversions.h>
37+
#include <octomap_ros/OctomapBinary.h>
3838

3939
#include <tf/transform_datatypes.h>
4040
#include <boost/foreach.hpp>
@@ -50,7 +50,7 @@ namespace octocostmap {
5050
pc_tf_filter_ = new tf::MessageFilter<pcl::PointCloud<pcl::PointXYZ> >(pc_sub_, tfl_, map_frame_, 100);
5151
pc_tf_filter_->registerCallback(boost::bind(&OctoCostmap::pointCloudCallback, this, _1));
5252

53-
map_pub_ = nh_.advertise<octomap_server::OctomapBinary>("octomap", 1, true);
53+
map_pub_ = nh_.advertise<octomap_ros::OctomapBinary>("octomap", 1, true);
5454

5555
octree_ = new octomap::OcTree(map_resolution_);
5656
}
@@ -115,8 +115,8 @@ namespace octocostmap {
115115

116116
void OctoCostmap::publishOctomapMsg() {
117117
if (map_pub_.getNumSubscribers() > 0) {
118-
octomap_server::OctomapBinary::Ptr map_ptr = boost::make_shared<octomap_server::OctomapBinary>();
119-
octomap_server::octomapMapToMsg(*octree_, *map_ptr);
118+
octomap_ros::OctomapBinary::Ptr map_ptr = boost::make_shared<octomap_ros::OctomapBinary>();
119+
octomap::octomapMapToMsg(*octree_, *map_ptr);
120120
map_ptr->header.frame_id = map_frame_;
121121
map_pub_.publish(map_ptr);
122122
ROS_DEBUG("Published an octocostmap");

0 commit comments

Comments
 (0)