38 #include <jsk_topic_tools/color_utils.h> 
   45                                                 "0 is fully transparent, 1.0 is fully opaque.",
 
   49       "Show name of each footstep",
 
   52       "Use Group Coloring", 
false,
 
   53       "Use footstep_group field to colorize footsteps",
 
   57       "width of the footstep, it's not used if the dimensions is specified in Footstep message.",
 
   61       "height of the footstep, it's not used if the dimensions is specified in Footstep message.",
 
   66       "depth of the footstep, it's not used if the dimensions is specified in Footstep message.",
 
   82       node->removeAndDestroyAllChildren();
 
   83       node->detachAllObjects();
 
  129     for (std::vector<jsk_footstep_msgs::Footstep>::const_iterator it = 
msg.footsteps.begin();
 
  130          it != 
msg.footsteps.end();
 
  176     if (num > 
texts_.size()) {
 
  178       for (
size_t i = 
texts_.size(); i < num; i++) {
 
  180         Ogre::SceneNode* node = 
scene_node_->createChildSceneNode();
 
  183         text->setVisible(
false);
 
  186         node->attachObject(
text);
 
  194         node->detachAllObjects();
 
  195         node->removeAndDestroyAllChildren();
 
  212       return std::min(a, 
b);
 
  218     for (
size_t i = 0; 
i < 
shapes_.size(); 
i++) {
 
  224         std_msgs::ColorRGBA color
 
  225           = jsk_topic_tools::colorCategory20(footstep.footstep_group);
 
  226         shape->setColor(color.r, color.g, color.b, 
alpha_);
 
  229         if (footstep.leg == jsk_footstep_msgs::Footstep::LLEG) {
 
  230           shape->setColor(0, 1, 0, 
alpha_);
 
  232         else if (footstep.leg == jsk_footstep_msgs::Footstep::RLEG) {
 
  233           shape->setColor(1, 0, 0, 
alpha_);
 
  235         else if (footstep.leg == jsk_footstep_msgs::Footstep::LARM) {
 
  238         else if (footstep.leg == jsk_footstep_msgs::Footstep::RARM) {
 
  239           shape->setColor(1, 0, 1, 
alpha_);
 
  242           shape->setColor(1, 1, 1, 
alpha_);
 
  250     const jsk_footstep_msgs::Footstep& footstep)
 
  252     if (footstep.dimensions.x == 0 &&
 
  253         footstep.dimensions.y == 0 &&
 
  254         footstep.dimensions.z == 0) {
 
  256                                             footstep.dimensions.y),
 
  257                                  footstep.dimensions.z),
 
  277     Ogre::Quaternion orientation;
 
  278     Ogre::Vector3 position;
 
  281                                                    position, orientation)) {
 
  282       std::ostringstream oss;
 
  283       oss << 
"Error transforming pose";
 
  284       oss << 
" from frame '" << 
msg->header.frame_id << 
"'";
 
  285       oss << 
" to frame '" << qPrintable(
fixed_frame_) << 
"'";
 
  299     for (
size_t i = 0; 
i < 
msg->footsteps.size(); 
i++)
 
  304       jsk_footstep_msgs::Footstep footstep = 
msg->footsteps[
i];
 
  305       Ogre::Vector3 step_position;
 
  306       Ogre::Vector3 shape_position;
 
  307       Ogre::Quaternion step_quaternion;
 
  312         std::ostringstream oss;
 
  313         oss << 
"Error transforming pose";
 
  314         oss << 
" from frame '" << 
msg->header.frame_id << 
"'";
 
  315         oss << 
" to frame '" << qPrintable(
fixed_frame_) << 
"'";
 
  321       Ogre::Vector3 step_offset (footstep.offset.x, footstep.offset.y, footstep.offset.z);
 
  322       shape_position = step_position + (step_quaternion * step_offset);
 
  324       shape->setPosition(shape_position);
 
  325       shape->setOrientation(step_quaternion);
 
  328       if (footstep.dimensions.x == 0 &&
 
  329           footstep.dimensions.y == 0 &&
 
  330           footstep.dimensions.z == 0) {
 
  336         scale[0] = footstep.dimensions.x;
 
  337         scale[1] = footstep.dimensions.y;
 
  338         scale[2] = footstep.dimensions.z;
 
  340       shape->setScale(
scale);      
 
  342       if (footstep.leg == jsk_footstep_msgs::Footstep::LLEG) {
 
  343         text->setCaption(
"LLEG");
 
  345       else if (footstep.leg == jsk_footstep_msgs::Footstep::RLEG) {
 
  346         text->setCaption(
"RLEG");
 
  348       else if (footstep.leg == jsk_footstep_msgs::Footstep::LARM) {
 
  349         text->setCaption(
"LARM");
 
  351       else if (footstep.leg == jsk_footstep_msgs::Footstep::RARM) {
 
  352         text->setCaption(
"RARM");
 
  355         text->setCaption(
"unknown");
 
  358       node->setPosition(shape_position);
 
  359       node->setOrientation(step_quaternion);