39 int main(
int argc,
char** argv)
41 ros::init(argc, argv,
"named_colors_demo");
47 unsigned int N = named_colors.size();
50 info.
width = (N - 1) / 3;
56 for (
unsigned int y = 0;
y < info.
height;
y++)
58 for (
unsigned int x = 0;
x < info.
width;
x++)
int main(int argc, char **argv)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
TFSIMD_FORCE_INLINE const tfScalar & y() const
void init(ros::NodeHandle &nh, const std::string &nav_grid_topic="grid", const std::string &occupancy_grid_topic="costmap", const std::string &update_area_topic="update_area", bool publish_updates=true, ros::Duration full_publish_cycle=ros::Duration(0), ros::Duration update_publish_cycle=ros::Duration(0))
const std::vector< ColorRGBA24 > & getNamedColors()
void setInfo(const NavGridInfo &new_info) override
TFSIMD_FORCE_INLINE const tfScalar & x() const
void setValue(const unsigned int x, const unsigned int y, const T &value) override
ROSCPP_DECL void spinOnce()