32 #include <map_organizer_msgs/OccupancyGridArray.h> 33 #include <std_msgs/Int32.h> 41 map_organizer_msgs::OccupancyGridArray
maps;
45 void cbMaps(
const map_organizer_msgs::OccupancyGridArray::Ptr& msg)
50 for (
auto& map :
maps.maps)
53 map.info.origin.position.z = 0.0;
56 void cbFloor(
const std_msgs::Int32::Ptr& msg)
61 int main(
int argc,
char** argv)
74 auto pubMap = neonavigation_common::compat::advertise<nav_msgs::OccupancyGrid>(
79 geometry_msgs::TransformStamped trans;
80 trans.header.frame_id =
"map_ground";
81 trans.child_frame_id =
"map";
91 if (
maps.maps.size() == 0)
108 tfb.sendTransform(trans);
map_organizer_msgs::OccupancyGridArray maps
std::vector< nav_msgs::MapMetaData > orig_mapinfos
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void cbMaps(const map_organizer_msgs::OccupancyGridArray::Ptr &msg)
ros::Subscriber subscribe(ros::NodeHandle &nh_new, const std::string &topic_new, ros::NodeHandle &nh_old, const std::string &topic_old, uint32_t queue_size, void(*fp)(M), const ros::TransportHints &transport_hints=ros::TransportHints())
int main(int argc, char **argv)
void cbFloor(const std_msgs::Int32::Ptr &msg)
ROSCPP_DECL void spinOnce()