2 #include <boost/format.hpp>
9 std::string &robot_name,
12 Ogre::ColourValue color,
13 Ogre::SceneManager *_scene_manager,
14 Ogre::SceneNode *_parent_node)
16 robot_name(robot_name),
17 scene_manager(_scene_manager),
18 frame_node(_parent_node),
66 circle->begin(
"BaseWhiteNoLighting", Ogre::RenderOperation::OT_LINE_STRIP);
71 double factor = 2.0 * M_PI / accuracy;
74 unsigned int point_index = 0;
75 for (; theta < 2.0*M_PI; theta += factor) {
80 circle->index(point_index++);
90 arrow->begin(
"BaseWhiteNoLighting", Ogre::RenderOperation::OT_TRIANGLE_LIST);
92 arrow->beginUpdate(0);
95 double factor = 2.0 * M_PI / accuracy;
98 unsigned int point_index = 0;
99 for (; point_index < accuracy; theta += factor) {
102 Ogre::Vector3 local_pose = Ogre::Vector3(c_theta, s_theta, 0);
103 Ogre::Matrix3 r_orient;
105 local_pose = r_orient * local_pose;
109 }
else if (point_index==1)
115 arrow->index(point_index++);
117 arrow->triangle(0,1,2);
141 text->setCharacterHeight(0.2);
145 text->setCaption(capt);
196 std::vector<std::string> mark_for_deletion;
200 auto dur = ts_now - elem.second;
203 mark_for_deletion.push_back(elem.first);
207 for (
const std::string &elem : mark_for_deletion)
222 return std::move(mark_for_deletion);
241 it->second->setDisabled();
256 it->second->render();
268 double robot_radius = _msg->shape_variables.size() ? _msg->shape_variables[0] : 1.0;
269 boost::circular_buffer<geometry_msgs::PoseWithCovariance> pose;
271 std::string rn = _msg->robot_name;
272 std::shared_ptr<RA> robot_attr = std::make_shared<RA>(
id_cnt++,
286 it->second->updatePose(_msg->pose);
287 it->second->robot_radius = _msg->shape_variables.size() ? _msg->shape_variables[0] : 1.0;
321 it.second->updateColor(color);