Go to the documentation of this file.
   48   m.
name = 
"projected_base_map";
 
   54   m.
name = 
"projected_spine_map";
 
   60   m.
name = 
"projected_arm_map";
 
   75   m_armLinks.push_back(
"l_gripper_l_finger_tip_link");
 
   77   m_armLinks.push_back(
"l_gripper_r_finger_tip_link");
 
   85   m_armLinks.push_back(
"r_gripper_l_finger_tip_link");
 
   87   m_armLinks.push_back(
"r_gripper_r_finger_tip_link");
 
  107   nav_msgs::MapMetaData gridmapInfo = 
m_gridmap.info;
 
  113   geometry_msgs::PointStamped vin;
 
  117   vin.header.stamp = rostime;
 
  118   double link_padding = 0.03;
 
  120   double minArmHeight = 2.0;
 
  121   double maxArmHeight = 0.0;
 
  123   for (
unsigned i = 0; i < 
m_armLinks.size(); ++i){
 
  125     geometry_msgs::PointStamped vout;
 
  126     const bool found_trans =
 
  129     ROS_ASSERT_MSG(found_trans, 
"Timed out waiting for transform to %s",
 
  133     minArmHeight = std::min(minArmHeight, vout.point.z - (
m_armLinkOffsets.at(i) + link_padding));
 
  135   ROS_INFO(
"Arm layer interval adjusted to (%f,%f)", minArmHeight, maxArmHeight);
 
  151     it->map.info.origin.position.z = it->z;
 
  153       ROS_INFO(
"Map resolution changed, rebuilding complete 2D maps");
 
  154       it->map.data.clear();
 
  156       it->map.data.resize(it->map.info.width * it->map.info.height, -1);
 
  157     } 
else if (mapInfoChanged){
 
  209   double z = it.getZ();
 
  210   double s2 = it.getSize()/2.0;
 
  216       inMapLevel[i] = 
true;
 
  221     unsigned idx = 
mapIdx(it.getKey());
 
  228     for (
unsigned i = 0; i < inMapLevel.size(); ++i){
 
  240     for(
int dx=0; dx < intSize; dx++){
 
  242       for(
int dy=0; dy < intSize; dy++){
 
  250         for (
unsigned i = 0; i < inMapLevel.size(); ++i){
 
  
octomap::OcTreeKey m_paddedMinKey
virtual void update2DMap(const OcTreeT::iterator &it, bool occupied)
updates the downprojected 2D map as either occupied or free
virtual void handlePreNodeTraversal(const ros::Time &rostime)
hook that is called before traversing all nodes
unsigned m_multires2DScale
virtual ~OctomapServerMultilayer()
Publisher advertise(AdvertiseOptions &ops)
MultilevelGrid m_multiGridmap
bool mapChanged(const nav_msgs::MapMetaData &oldMapInfo, const nav_msgs::MapMetaData &newMapInfo)
void adjustMapData(nav_msgs::OccupancyGrid &map, const nav_msgs::MapMetaData &oldMapInfo) const
nav_msgs::OccupancyGrid m_gridmap
#define ROS_ASSERT_MSG(cond,...)
virtual void handlePreNodeTraversal(const ros::Time &rostime)
hook that is called after traversing all nodes
unsigned mapIdx(int i, int j) const
virtual void handlePostNodeTraversal(const ros::Time &rostime)
hook that is called after traversing all nodes
std::vector< ros::Publisher * > m_multiMapPub
tf::TransformListener m_tfListener
bool m_projectCompleteMap
std::vector< double > m_armLinkOffsets
virtual void handlePostNodeTraversal(const ros::Time &rostime)
hook that is called after traversing all nodes
std::vector< std::string > m_armLinks
octomap_server
Author(s): Armin Hornung
autogenerated on Mon Jan 2 2023 03:18:15