30 #include <OGRE/OgreSceneNode.h>
31 #include <OGRE/OgreSceneManager.h>
32 #include <OGRE/OgreEntity.h>
42 #include <tuw_multi_robot_msgs/RobotGoals.h>
43 #include <tuw_multi_robot_msgs/RobotGoalsArray.h>
51 : moving_flag_node_(
NULL), current_flag_property_(
NULL)
74 arrow_->getSceneNode()->setVisible(
false);
104 if (currentRobotNr_ < nr_robots_->getInt())
142 fn->detachAllObjects();
143 fn->removeAndDestroyAllChildren();
177 double cy = cos(yaw * 0.5);
178 double sy = sin(yaw * 0.5);
179 double cr = cos(roll * 0.5);
180 double sr = sin(roll * 0.5);
181 double cp = cos(pitch * 0.5);
182 double sp = sin(pitch * 0.5);
184 q.w = cy * cr * cp + sy * sr * sp;
185 q.x = cy * sr * cp - sy * cr * sp;
186 q.y = cy * cr * sp + sy * sr * cp;
187 q.z = sy * cr * cp - cy * sr * sp;
192 double cy = cos(yaw * 0.5);
193 double sy = sin(yaw * 0.5);
194 double cr = cos(roll * 0.5);
195 double sr = sin(roll * 0.5);
196 double cp = cos(pitch * 0.5);
197 double sp = sin(pitch * 0.5);
199 q.w = cy * cr * cp + sy * sr * sp;
200 q.x = cy * sr * cp - sy * cr * sp;
201 q.y = cy * cr * sp + sy * sr * cp;
202 q.z = sy * cr * cp - cy * sr * sp;
212 Ogre::Vector3 intersection;
213 Ogre::Plane ground_plane(Ogre::Vector3::UNIT_Z, 0.0
f);
219 event.
x, event.
y, intersection))
228 arrow_->setPosition(intersection);
229 arrow_->getSceneNode()->setVisible(
true);
231 state_ = state::Orientation;
235 }
else if (event.
type == QEvent::MouseMove && event.
left()) {
238 Ogre::Vector3 cur_pos;
239 Ogre::Plane ground_plane( Ogre::Vector3::UNIT_Z, 0.0
f );
243 event.
x, event.
y, cur_pos ))
245 double angle = atan2( cur_pos.y -
arrow_->getPosition().y, cur_pos.x -
arrow_->getPosition().x );
248 Ogre::Quaternion orient_x = Ogre::Quaternion( Ogre::Radian(-Ogre::Math::HALF_PI), Ogre::Vector3::UNIT_Y );
250 arrow_->setOrientation( Ogre::Quaternion( Ogre::Radian(
angle), Ogre::Vector3::UNIT_Z ) * orient_x );
252 Ogre::Quaternion q_from_angle;
258 }
else if (event.
leftUp()) {
260 if (
state_ == state::Orientation)
263 Ogre::Vector3 cur_pos;
264 Ogre::Plane ground_plane( Ogre::Vector3::UNIT_Z, 0.0
f );
267 event.
x, event.
y, cur_pos ))
269 double angle = atan2( cur_pos.y -
arrow_->getPosition().y, cur_pos.x -
arrow_->getPosition().x );
271 Ogre::Quaternion q_from_angle;
284 arrow_->getSceneNode()->setVisible(
false);
288 tuw_multi_robot_msgs::RobotGoalsArray array;
292 tuw_multi_robot_msgs::RobotGoals goals;
294 geometry_msgs::Pose pose;
295 pose.position.x = position.x;
296 pose.position.y = position.y;
297 pose.position.z = 0.0;
299 goals.destinations.push_back(pose);
302 array.robots.push_back(goals);
320 event.
x, event.
y, intersection))
325 double length = Ogre::Vector3(0,0,0).distance(intersection);
340 Ogre::Quaternion orient_x = Ogre::Quaternion( Ogre::Radian(-Ogre::Math::HALF_PI), Ogre::Vector3::UNIT_Y );
341 arrow_robot2flag_->setOrientation( Ogre::Quaternion( Ogre::Radian(
angle), Ogre::Vector3::UNIT_Z ) * orient_x );
353 Ogre::SceneNode *node =
scene_manager_->getRootSceneNode()->createChildSceneNode();
355 node->attachObject(entity);
356 node->setVisible(
true);
357 node->setPosition(position);
358 node->setOrientation(orientation);
361 node->getAttachedObject(0)->getBoundingBox().getSize().z + 0.15));