map.h 1.0 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253
  1. /************************************************************
  2. *
  3. * Copyright (c) 2021, University of California, Los Angeles
  4. *
  5. * Authors: Kenny J. Chen, Brett T. Lopez
  6. * Contact: kennyjchen@ucla.edu, btlopez@ucla.edu
  7. *
  8. ***********************************************************/
  9. #include "dlo/dlo.h"
  10. class dlo::MapNode {
  11. public:
  12. MapNode(ros::NodeHandle node_handle);
  13. ~MapNode();
  14. static void abort() {
  15. abort_ = true;
  16. }
  17. void start();
  18. void stop();
  19. private:
  20. void abortTimerCB(const ros::TimerEvent& e);
  21. void publishTimerCB(const ros::TimerEvent& e);
  22. void keyframeCB(const sensor_msgs::PointCloud2ConstPtr& keyframe);
  23. void getParams();
  24. ros::NodeHandle nh;
  25. ros::Timer abort_timer;
  26. ros::Timer publish_timer;
  27. ros::Subscriber keyframe_sub;
  28. ros::Publisher map_pub;
  29. pcl::PointCloud<PointType>::Ptr dlo_map;
  30. pcl::VoxelGrid<PointType> voxelgrid;
  31. ros::Time map_stamp;
  32. std::string odom_frame;
  33. double publish_freq_;
  34. double leaf_size_;
  35. static std::atomic<bool> abort_;
  36. };