37 TrackingOctomapServer::TrackingOctomapServer(
const std::string& filename) :
50 ROS_ERROR(
"Could not open requested file %s, exiting.", filename.c_str());
57 std::string changeSetTopic =
"changes";
58 std::string changeIdFrame =
"/talker/changes";
60 private_nh.
param(
"topic_changes", changeSetTopic, changeSetTopic);
67 ROS_WARN(
"OctoMapServer: It might not be useful to publish changes and at the same time listen to them." 68 "Setting 'track_changes' to false!");
101 pcl::PointCloud<pcl::PointXYZI> changedCells = pcl::PointCloud<pcl::PointXYZI>();
104 for (KeyBoolMap::const_iterator iter = startPnt; iter != endPnt; ++iter) {
118 pnt.intensity = 1000;
121 pnt.intensity = -1000;
124 changedCells.push_back(pnt);
129 sensor_msgs::PointCloud2 changed;
134 ROS_DEBUG(
"[server] sending %d changed entries", (
int)changedCells.size());
142 pcl::PointCloud<pcl::PointXYZI> cells;
144 ROS_DEBUG(
"[client] size of newly occupied cloud: %i", (
int)cells.points.size());
146 for (
size_t i = 0; i < cells.points.size(); i++) {
147 pcl::PointXYZI& pnt = cells.points[i];
void insertScan(const tf::Point &sensorOrigin, const PCLPointCloud &ground, const PCLPointCloud &nonground)
update occupancy map with a scan labeled as ground and nonground. The scans should be in the global m...
void updateInnerOccupancy()
void publish(const boost::shared_ptr< M > &message) const
unsigned short int coordToKey(double coordinate) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
virtual OcTreeNode * updateNode(const OcTreeKey &key, float log_odds_update, bool lazy_eval=false)
ros::Subscriber subChangeSet
OcTreeNode * search(double x, double y, double z, unsigned int depth=0) const
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
unsigned int getTreeDepth() const
virtual ~TrackingOctomapServer()
void trackCallback(sensor_msgs::PointCloud2Ptr cloud)
double keyToCoord(unsigned short int key, unsigned depth) const
std::string change_id_frame
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
virtual void insertScan(const tf::Point &sensorOrigin, const PCLPointCloud &ground, const PCLPointCloud &nonground)
update occupancy map with a scan labeled as ground and nonground. The scans should be in the global m...
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
KeyBoolMap::const_iterator changedKeysBegin() const
double getResolution() const
virtual void publishAll(const ros::Time &rostime=ros::Time::now())
bool readBinary(std::istream &s)
void resetChangeDetection()
void toROSMsg(const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)
ros::Publisher pubChangeSet
void enableChangeDetection(bool enable)
nav_msgs::OccupancyGrid m_gridmap
pcl::PointCloud< pcl::PointXYZ > PCLPointCloud
size_t calcNumNodes() const
bool isNodeOccupied(const OcTreeNode *occupancyNode) const
virtual size_t size() const
KeyBoolMap::const_iterator changedKeysEnd() const