Revision: 6900 http://playerstage.svn.sourceforge.net/playerstage/?rev=6900&view=rev Author: natepak Date: 2008-07-22 16:14:59 +0000 (Tue, 22 Jul 2008)
Log Message: ----------- Added mouse picking. Modified Paths: -------------- code/gazebo/trunk/server/Entity.cc code/gazebo/trunk/server/Model.cc code/gazebo/trunk/server/Model.hh code/gazebo/trunk/server/Simulator.cc code/gazebo/trunk/server/Simulator.hh code/gazebo/trunk/server/gui/GLWindow.cc code/gazebo/trunk/server/gui/GLWindow.hh code/gazebo/trunk/server/physics/Body.cc code/gazebo/trunk/server/physics/Body.hh code/gazebo/trunk/server/physics/Geom.cc code/gazebo/trunk/server/physics/ode/ODEPhysics.cc code/gazebo/trunk/server/physics/ode/ODEPhysics.hh code/gazebo/trunk/server/rendering/OgreAdaptor.cc code/gazebo/trunk/server/rendering/OgreAdaptor.hh code/gazebo/trunk/server/rendering/OgreVisual.cc code/gazebo/trunk/server/rendering/OgreVisual.hh code/gazebo/trunk/server/rendering/UserCamera.cc code/gazebo/trunk/worlds/simpleshapes.world Modified: code/gazebo/trunk/server/Entity.cc =================================================================== --- code/gazebo/trunk/server/Entity.cc 2008-07-21 23:39:22 UTC (rev 6899) +++ code/gazebo/trunk/server/Entity.cc 2008-07-22 16:14:59 UTC (rev 6900) @@ -24,6 +24,8 @@ * Date: 03 Apr 2007 * SVN: $Id$ */ + +#include "Body.hh" #include "GazeboError.hh" #include "Global.hh" #include "OgreVisual.hh" @@ -134,7 +136,19 @@ // Set whether this entity is static: immovable void Entity::SetStatic(bool s) { + std::vector< Entity *>::iterator iter; + Body *body = NULL; + this->isStatic = s; + + for (iter = this->children.begin(); iter != this->children.end(); iter++) + { + (*iter)->SetStatic(s); + body = dynamic_cast<Body*>(*iter); + if (body) + body->SetEnabled(!s); + } + } //////////////////////////////////////////////////////////////////////////////// Modified: code/gazebo/trunk/server/Model.cc =================================================================== --- code/gazebo/trunk/server/Model.cc 2008-07-21 23:39:22 UTC (rev 6899) +++ code/gazebo/trunk/server/Model.cc 2008-07-22 16:14:59 UTC (rev 6900) @@ -174,11 +174,6 @@ } -void Model::Test() -{ - std::cout << "this is a test\n"; -} - void Model::Save() { /*std::map<std::string, Body* >::iterator bodyIter; @@ -290,11 +285,9 @@ boost::python::call<void>(this->pFuncUpdate, this); }*/ - Body *b = NULL; if (!this->canonicalBodyName.empty()) { this->pose = this->bodies[this->canonicalBodyName]->GetPose(); - b = this->bodies[this->canonicalBodyName]; } return this->UpdateChild(); Modified: code/gazebo/trunk/server/Model.hh =================================================================== --- code/gazebo/trunk/server/Model.hh 2008-07-21 23:39:22 UTC (rev 6899) +++ code/gazebo/trunk/server/Model.hh 2008-07-22 16:14:59 UTC (rev 6900) @@ -66,7 +66,6 @@ /// \brief Save the model public: void Save(); - public: void Test(); /// \brief Initialize the model public: int Init(); Modified: code/gazebo/trunk/server/Simulator.cc =================================================================== --- code/gazebo/trunk/server/Simulator.cc 2008-07-21 23:39:22 UTC (rev 6899) +++ code/gazebo/trunk/server/Simulator.cc 2008-07-22 16:14:59 UTC (rev 6900) @@ -28,6 +28,9 @@ #include <fstream> #include <sys/time.h> +#include "Model.hh" +#include "Entity.hh" +#include "OgreVisual.hh" #include "World.hh" #include "Gui.hh" #include "XMLConfig.hh" @@ -466,3 +469,33 @@ { return this->physicsEnabled; } + +//////////////////////////////////////////////////////////////////////////////// +/// Set the selected entity +void Simulator::SetSelectedEntity( Entity *ent ) +{ + if (this->selectedEntity) + { + this->selectedEntity->GetVisualNode()->ShowSelectionBox(false); + this->selectedEntity->SetStatic(false); + } + + if (this->selectedEntity != ent) + { + this->selectedEntity = ent; + this->selectedEntity->GetVisualNode()->ShowSelectionBox(true); + this->selectedEntity->SetStatic(true); + } + else + this->selectedEntity = NULL; + +} + +//////////////////////////////////////////////////////////////////////////////// +/// Get the selected entity +Entity *Simulator::GetSelectedEntity() const +{ + return this->selectedEntity; +} + + Modified: code/gazebo/trunk/server/Simulator.hh =================================================================== --- code/gazebo/trunk/server/Simulator.hh 2008-07-21 23:39:22 UTC (rev 6899) +++ code/gazebo/trunk/server/Simulator.hh 2008-07-22 16:14:59 UTC (rev 6900) @@ -44,6 +44,7 @@ class XMLConfigNode; class GazeboConfig; class OgreAdaptor; + class Entity; /// \brief The World /* @@ -157,6 +158,12 @@ /// \brief Get the physics enabled/disabled public: bool GetPhysicsEnabled() const; + /// \brief Set the selected entity + public: void SetSelectedEntity( Entity *ent ); + + /// \brief Get the selected entity + public: Entity *GetSelectedEntity() const; + ///pointer to the XML Data private: XMLConfig *xmlFile; @@ -213,6 +220,9 @@ /// Length of time the simulation should run private: double timeout; + /// The entity currently selected by the user + private: Entity *selectedEntity; + //Singleton implementation private: friend class DestroyerT<Simulator>; private: friend class SingletonT<Simulator>; Modified: code/gazebo/trunk/server/gui/GLWindow.cc =================================================================== --- code/gazebo/trunk/server/gui/GLWindow.cc 2008-07-21 23:39:22 UTC (rev 6899) +++ code/gazebo/trunk/server/gui/GLWindow.cc 2008-07-22 16:14:59 UTC (rev 6900) @@ -24,6 +24,7 @@ * SVN: $Id:$ */ +#include "Model.hh" #include <X11/keysym.h> #include <X11/Xlib.h> #include <X11/Xutil.h> @@ -32,6 +33,7 @@ #include <GL/glx.h> +#include "Entity.hh" #include "OgreCamera.hh" #include "OgreCreator.hh" #include "Simulator.hh" @@ -195,7 +197,11 @@ if (!this->mouseDrag) { - //Entity *ent = World::Instance()->GetEntityAt(this->mousePos); + Entity *ent = OgreAdaptor::Instance()->GetEntityAt(this->activeCamera, this->mousePos); + if (ent) + { + Simulator::Instance()->SetSelectedEntity( ent ); + } } this->mouseDrag = false; @@ -207,18 +213,44 @@ { if (this->activeCamera && this->activeCamera->GetUserMovable()) { + Vector2<int> d = this->mousePos - this->prevMousePos; if (this->leftMousePressed) { - Vector2<int> d = this->mousePos - this->prevMousePos; this->activeCamera->RotateYaw(DTOR(-d.x * this->rotateAmount)); this->activeCamera->RotatePitch(DTOR(d.y * this->rotateAmount)); } + else if (this->rightMousePressed) + { + Model *model = dynamic_cast<Model*>(Simulator::Instance()->GetSelectedEntity()); + if (model) + { + Pose3d pose = model->GetPose(); + pose.pos.y -= d.x * 0.05; + pose.pos.x -= d.y * 0.05; + model->SetPose(pose); + } + } + } this->mouseDrag = true; } //////////////////////////////////////////////////////////////////////////////// +// Handle mouse wheel movement +void GLWindow::HandleMouseWheel(int dx, int dy) +{ + Model *model = dynamic_cast<Model*>(Simulator::Instance()->GetSelectedEntity()); + if (model) + { + Pose3d pose = model->GetPose(); + pose.pos.z += dy * 0.05; + model->SetPose(pose); + } + +} + +//////////////////////////////////////////////////////////////////////////////// /// Handle a key press void GLWindow::HandleKeyPress(int keyNum) { @@ -380,6 +412,11 @@ handled = true; break; + case FL_MOUSEWHEEL: + this->HandleMouseWheel(Fl::event_dx(), Fl::event_dy()); + handled = true; + break; + default: break; } Modified: code/gazebo/trunk/server/gui/GLWindow.hh =================================================================== --- code/gazebo/trunk/server/gui/GLWindow.hh 2008-07-21 23:39:22 UTC (rev 6899) +++ code/gazebo/trunk/server/gui/GLWindow.hh 2008-07-22 16:14:59 UTC (rev 6900) @@ -113,6 +113,8 @@ /// \brief Handle a key release private: void HandleKeyRelease(int keyNum); + /// \brief Handle mouse wheel movement + private: void HandleMouseWheel(int dx, int dy); /// ID of the window private: Window windowId; Modified: code/gazebo/trunk/server/physics/Body.cc =================================================================== --- code/gazebo/trunk/server/physics/Body.cc 2008-07-21 23:39:22 UTC (rev 6899) +++ code/gazebo/trunk/server/physics/Body.cc 2008-07-22 16:14:59 UTC (rev 6900) @@ -51,16 +51,11 @@ Body::Body(Entity *parent, dWorldID worldId) : Entity(parent) { - if (!this->IsStatic()) - { - this->bodyId = dBodyCreate(worldId); + this->bodyId = dBodyCreate(worldId); - dMassSetZero( &this->mass ); - } - else - { - this->bodyId = NULL; - } + dMassSetZero( &this->mass ); + + this->SetEnabled(!this->IsStatic()); } @@ -163,8 +158,7 @@ // Set whether gravity affects this body void Body::SetGravityMode(bool mode) { - if (this->bodyId) - dBodySetGravityMode(this->bodyId, mode); + dBodySetGravityMode(this->bodyId, mode); } //////////////////////////////////////////////////////////////////////////////// @@ -191,11 +185,16 @@ if (!this->IsStatic()) { + //this->SetEnabled(true); Pose3d pose = this->GetPose(); // Set the pose of the scene node this->visualNode->SetPose(pose); } + else + { + this->SetEnabled(false); + } for (geomIter=this->geoms.begin(); geomIter!=this->geoms.end(); geomIter++) @@ -214,7 +213,7 @@ // Attach a geom to this body void Body::AttachGeom( Geom *geom ) { - if (this->bodyId) + //if (this->bodyId) { if (geom->IsPlaceable()) { @@ -232,73 +231,35 @@ // Set the pose of the body void Body::SetPose(const Pose3d &pose) { - if (this->IsStatic()) - { - std::vector< Geom* >::iterator giter; - PlaneGeom *plane = NULL; - this->staticPose = pose; + Pose3d localPose; - this->SetPosition(this->staticPose.pos); - this->SetRotation(this->staticPose.rot); + // Compute pose of CoM + localPose = this->comPose + pose; - // Hack to fix the altitude of the ODE plane - for (giter = this->geoms.begin(); giter != this->geoms.end(); giter++) - { - if ((*giter)->GetGeomClass() == dPlaneClass) - { - plane = dynamic_cast<PlaneGeom*>(*giter); - plane->SetAltitude(pose.pos); - } - else - (*giter)->SetImmovableBasePose(this->staticPose); - } - } - else - { - Pose3d localPose; - - // Compute pose of CoM - localPose =this->comPose + pose; - - this->SetPosition(localPose.pos); - this->SetRotation(localPose.rot); - } + this->SetPosition(localPose.pos); + this->SetRotation(localPose.rot); } //////////////////////////////////////////////////////////////////////////////// // Return the pose of the body Pose3d Body::GetPose() const { - if (this->IsStatic()) - return this->staticPose; - else - { - Pose3d pose; + Pose3d pose; - pose.pos = this->GetPosition(); - pose.rot = this->GetRotation(); + pose.pos = this->GetPosition(); + pose.rot = this->GetRotation(); - pose = this->comPose.CoordPoseSolve(pose); + pose = this->comPose.CoordPoseSolve(pose); - return pose; - } + return pose; } //////////////////////////////////////////////////////////////////////////////// // Set the position of the body void Body::SetPosition(const Vector3 &pos) { + dBodySetPosition(this->bodyId, pos.x, pos.y, pos.z); - if (!this->IsStatic()) - { - // Set the position of the ODE body - dBodySetPosition(this->bodyId, pos.x, pos.y, pos.z); - } - else - { - this->staticPose.pos = pos; - } - // Set the position of the scene node this->visualNode->SetPosition(pos); } @@ -307,23 +268,15 @@ // Set the rotation of the body void Body::SetRotation(const Quatern &rot) { - if (!this->IsStatic()) - { - dQuaternion q; - q[0] = rot.u; - q[1] = rot.x; - q[2] = rot.y; - q[3] = rot.z; + dQuaternion q; + q[0] = rot.u; + q[1] = rot.x; + q[2] = rot.y; + q[3] = rot.z; - // Set the rotation of the ODE body - dBodySetQuaternion(this->bodyId, q); + // Set the rotation of the ODE body + dBodySetQuaternion(this->bodyId, q); - } - else - { - this->staticPose.rot = rot; - } - // Set the orientation of the scene node this->visualNode->SetRotation(rot); } @@ -332,22 +285,16 @@ // Return the position of the body. in global CS Vector3 Body::GetPosition() const { + Vector3 pos; + const dReal *p; - if (!this->IsStatic()) - { - Vector3 pos; - const dReal *p; + p = dBodyGetPosition(this->bodyId); - p = dBodyGetPosition(this->bodyId); + pos.x = p[0]; + pos.y = p[1]; + pos.z = p[2]; - pos.x = p[0]; - pos.y = p[1]; - pos.z = p[2]; - - return pos; - } - else - return this->staticPose.pos; + return pos; } @@ -355,23 +302,17 @@ // Return the rotation Quatern Body::GetRotation() const { - if (!this->IsStatic()) - { - Quatern rot; - const dReal *r; + Quatern rot; + const dReal *r; - r = dBodyGetQuaternion(this->bodyId); + r = dBodyGetQuaternion(this->bodyId); - rot.u = r[0]; - rot.x = r[1]; - rot.y = r[2]; - rot.z = r[3]; + rot.u = r[0]; + rot.x = r[1]; + rot.y = r[2]; + rot.z = r[3]; - return rot; - } - else - return this->staticPose.rot; - + return rot; } //////////////////////////////////////////////////////////////////////////////// @@ -477,10 +418,6 @@ Pose3d oldPose, newPose, pose; std::vector< Geom* >::iterator giter; - // Dummy bodies dont have mass - if (!this->bodyId) - return; - // Construct the mass matrix by combining all the geoms dMassSetZero( &this->mass ); @@ -552,12 +489,7 @@ /// Set the velocity of the body void Body::SetLinearVel(const Vector3 &vel) { - if (!this->bodyId) - { - gzmsg(0) << "Invalid ODE body\n"; - } - else - dBodySetLinearVel(this->bodyId, vel.x, vel.y, vel.z); + dBodySetLinearVel(this->bodyId, vel.x, vel.y, vel.z); } //////////////////////////////////////////////////////////////////////////////// @@ -567,12 +499,6 @@ Vector3 vel; const dReal *dvel; - if (!this->bodyId) - { - gzmsg(0) << "Invalid ODE body\n"; - return vel; - } - dvel = dBodyGetLinearVel(this->bodyId); vel.x = dvel[0]; @@ -586,12 +512,7 @@ /// Set the velocity of the body void Body::SetAngularVel(const Vector3 &vel) { - if (!this->bodyId) - { - gzmsg(0) << "Invalid ODE body\n"; - } - else - dBodySetAngularVel(this->bodyId, vel.x, vel.y, vel.z); + dBodySetAngularVel(this->bodyId, vel.x, vel.y, vel.z); } //////////////////////////////////////////////////////////////////////////////// @@ -601,12 +522,6 @@ Vector3 vel; const dReal *dvel; - if (!this->bodyId) - { - gzmsg(0) << "Invalid ODE body\n"; - return vel; - } - dvel = dBodyGetAngularVel(this->bodyId); vel.x = dvel[0]; @@ -619,12 +534,7 @@ /// \brief Set the force applied to the body void Body::SetForce(const Vector3 &force) { - if (!this->bodyId) - { - gzmsg(0) << "Invalid ODE body\n"; - } - else - dBodySetForce(this->bodyId, force.x, force.y, force.z); + dBodySetForce(this->bodyId, force.x, force.y, force.z); } //////////////////////////////////////////////////////////////////////////////// @@ -634,12 +544,6 @@ Vector3 force; const dReal *dforce; - if (!this->bodyId) - { - gzmsg(0) << "Invalid ODE body\n"; - return force; - } - dforce = dBodyGetForce(this->bodyId); force.x = dforce[0]; @@ -653,12 +557,7 @@ /// \brief Set the torque applied to the body void Body::SetTorque(const Vector3 &torque) { - if (!this->bodyId) - { - gzmsg(0) << "Invalid ODE body\n"; - } - else - dBodySetTorque(this->bodyId, torque.x, torque.y, torque.z); + dBodySetTorque(this->bodyId, torque.x, torque.y, torque.z); } //////////////////////////////////////////////////////////////////////////////// @@ -668,13 +567,6 @@ Vector3 torque; const dReal *dtorque; - if (!this->bodyId) - { - gzmsg(0) << "Invalid ODE body\n"; - return torque; - } - - dtorque = dBodyGetTorque(this->bodyId); torque.x = dtorque[0]; Modified: code/gazebo/trunk/server/physics/Body.hh =================================================================== --- code/gazebo/trunk/server/physics/Body.hh 2008-07-21 23:39:22 UTC (rev 6899) +++ code/gazebo/trunk/server/physics/Body.hh 2008-07-22 16:14:59 UTC (rev 6900) @@ -168,7 +168,6 @@ private: bool isStatic; private: Pose3d comPose; - private: Pose3d staticPose; }; /// \} Modified: code/gazebo/trunk/server/physics/Geom.cc =================================================================== --- code/gazebo/trunk/server/physics/Geom.cc 2008-07-21 23:39:22 UTC (rev 6899) +++ code/gazebo/trunk/server/physics/Geom.cc 2008-07-22 16:14:59 UTC (rev 6900) @@ -122,7 +122,7 @@ childNode = node->GetChild("visual"); while (childNode) { - OgreVisual *visual = new OgreVisual(this->visualNode); + OgreVisual *visual = new OgreVisual(this->visualNode, this); visual->Load(childNode); this->visuals.push_back(visual); childNode = childNode->GetNext("visual"); Modified: code/gazebo/trunk/server/physics/ode/ODEPhysics.cc =================================================================== --- code/gazebo/trunk/server/physics/ode/ODEPhysics.cc 2008-07-21 23:39:22 UTC (rev 6899) +++ code/gazebo/trunk/server/physics/ode/ODEPhysics.cc 2008-07-22 16:14:59 UTC (rev 6900) @@ -165,15 +165,12 @@ { entity->spaceId = entity->GetParent()->spaceId; } - - this->entities[entity->GetId()] = entity; } //////////////////////////////////////////////////////////////////////////////// // Remove an entity from the physics engine void ODEPhysics::RemoveEntity(Entity *entity) { - this->entities.erase(entity->GetId()); } //////////////////////////////////////////////////////////////////////////////// @@ -262,25 +259,24 @@ double h, kp, kd; contact.geom = contactGeoms[i]; - contact.surface.mode = 0; + contact.surface.mode = dContactSoftERP | dContactSoftCFM | + dContactBounce | dContactMu2; + // Compute the CFM and ERP by assuming the two bodies form a // spring-damper system. h = self->stepTime; kp = 1 / (1 / geom1->contact->kp + 1 / geom2->contact->kp); kd = geom1->contact->kd + geom2->contact->kd; - contact.surface.mode |= dContactSoftERP | dContactSoftCFM; contact.surface.soft_erp = h * kp / (h * kp + kd); contact.surface.soft_cfm = 1 / (h * kp + kd); - //contacts[i].surface.mode |= dContactBounce | dContactSoftCFM; - contact.surface.mode |= dContactApprox1; contact.surface.mu = MIN(geom1->contact->mu1, geom2->contact->mu1); - contact.surface.mu2 = 0; + contact.surface.mu2 = MIN(geom1->contact->mu2, geom2->contact->mu2); contact.surface.bounce = 0.1; contact.surface.bounce_vel = 0.1; - //contacts[i].surface.soft_cfm = 0.01; + contact.surface.soft_cfm = 0.01; dJointID c = dJointCreateContact (self->worldId, self->contactGroup, &contact); Modified: code/gazebo/trunk/server/physics/ode/ODEPhysics.hh =================================================================== --- code/gazebo/trunk/server/physics/ode/ODEPhysics.hh 2008-07-21 23:39:22 UTC (rev 6899) +++ code/gazebo/trunk/server/physics/ode/ODEPhysics.hh 2008-07-22 16:14:59 UTC (rev 6900) @@ -28,11 +28,9 @@ #define ODEPHYSICS_HH #include <ode/ode.h> -#include <map> #include "PhysicsEngine.hh" - namespace gazebo { class SphereGeom; @@ -131,9 +129,6 @@ /// \brief Collision attributes private: dJointGroupID contactGroup; - /// List of all the entities - private: std::map<int, Entity* > entities; - private: double globalCFM; private: double globalERP; }; Modified: code/gazebo/trunk/server/rendering/OgreAdaptor.cc =================================================================== --- code/gazebo/trunk/server/rendering/OgreAdaptor.cc 2008-07-21 23:39:22 UTC (rev 6899) +++ code/gazebo/trunk/server/rendering/OgreAdaptor.cc 2008-07-22 16:14:59 UTC (rev 6900) @@ -34,6 +34,8 @@ #include <iostream> #include <string.h> +#include "Model.hh" +#include "OgreVisual.hh" #include "UserCamera.hh" #include "MovableText.hh" #include "OgreHUD.hh" @@ -273,6 +275,8 @@ this->updateRate = node->GetDouble("maxUpdateRate",0,0); this->raySceneQuery = this->sceneMgr->createRayQuery( Ogre::Ray() ); + this->raySceneQuery->setSortByDistance(true); + this->raySceneQuery->setQueryMask(Ogre::SceneManager::ENTITY_TYPE_MASK); } //////////////////////////////////////////////////////////////////////////////// @@ -466,30 +470,50 @@ //////////////////////////////////////////////////////////////////////////////// /// Get an entity at a pixel location using a camera. Used for mouse picking. -Entity *OgreAdaptor::GetEntityAt(OgreCamera *camera, int x, int y) +Entity *OgreAdaptor::GetEntityAt(OgreCamera *camera, Vector2<int> mousePos) { - /* - Ogre::Vector3 camPos = camera->getPosition(); + Entity *entity = NULL; + Ogre::Camera *ogreCam = camera->GetOgreCamera(); + Ogre::Vector3 camPos = ogreCam->getPosition(); - Ogre::Ray mouseRay = camera->getCameraToViewportRay( - x/camera->GetViewportWidth(), y/camera->GetViewportHeight()); + Ogre::Ray mouseRay = ogreCam->getCameraToViewportRay( + (float)mousePos.x / ogreCam->getViewport()->getActualWidth(), + (float)mousePos.y / ogreCam->getViewport()->getActualHeight() ); this->raySceneQuery->setRay( mouseRay ); // Perform the scene query Ogre::RaySceneQueryResult &result = this->raySceneQuery->execute(); Ogre::RaySceneQueryResult::iterator iter = result.begin(); - - // Get the results, set the camera height - if (iter != result.end() && iter->worldFragment) + + for (iter = result.begin(); iter != result.end(); iter++) { - Ogre::Real terrainHeight = iter->worldFragment->singleIntersection.y; - if ((terrainHeight + 10.0f) > camPos.y) - camera->setPosition( camPos.x, terrainHeight + 10.0f, camPos.z); + if (iter->movable) + { + + OgreVisual *vis = dynamic_cast<OgreVisual*>(iter->movable->getUserObject()); + if (vis && vis->GetEntity()) + { + entity = vis->GetEntity(); + entity->GetVisualNode()->ShowSelectionBox(true); + Model *model = NULL; + + do + { + model = dynamic_cast<Model*>(entity); + entity = entity->GetParent(); + } while (model == NULL); + + return model; + } + } + } - */ + + return NULL; } + //////////////////////////////////////////////////////////////////////////////// /// Get the desired update rate double OgreAdaptor::GetUpdateRate() Modified: code/gazebo/trunk/server/rendering/OgreAdaptor.hh =================================================================== --- code/gazebo/trunk/server/rendering/OgreAdaptor.hh 2008-07-21 23:39:22 UTC (rev 6899) +++ code/gazebo/trunk/server/rendering/OgreAdaptor.hh 2008-07-22 16:14:59 UTC (rev 6900) @@ -31,6 +31,7 @@ #include <X11/Xutil.h> #include <GL/glx.h> +#include "Vector2.hh" #include "SingletonT.hh" namespace Ogre @@ -97,7 +98,7 @@ /// \brief Get an entity at a pixel location using a camera. Used for /// mouse picking. - public: Entity *GetEntityAt(OgreCamera *camera, int x, int y); + public: Entity *GetEntityAt(OgreCamera *camera, Vector2<int> mousePos); private: void LoadPlugins(); private: void SetupResources(); Modified: code/gazebo/trunk/server/rendering/OgreVisual.cc =================================================================== --- code/gazebo/trunk/server/rendering/OgreVisual.cc 2008-07-21 23:39:22 UTC (rev 6899) +++ code/gazebo/trunk/server/rendering/OgreVisual.cc 2008-07-22 16:14:59 UTC (rev 6900) @@ -24,6 +24,7 @@ * SVN: $Id:$ */ #include <Ogre.h> +#include "Entity.hh" #include "Global.hh" #include "GazeboMessage.hh" #include "GazeboError.hh" @@ -37,7 +38,7 @@ //////////////////////////////////////////////////////////////////////////////// // Constructor -OgreVisual::OgreVisual(OgreVisual *node) +OgreVisual::OgreVisual(OgreVisual *node, Entity *owner) { std::ostringstream stream; @@ -52,10 +53,10 @@ //FIXME: what if we add the capability to delete and add new children? stream << this->parentNode->getName() << "_VISUAL_" << visualCounter++; - // Create the scene node this->sceneNode = this->parentNode->createChildSceneNode( stream.str() ); + this->entity = owner; this->staticGeometry = NULL; this->boundingBoxNode = NULL; @@ -100,7 +101,7 @@ try { // Create the entity - stream << this->sceneNode->getName() << "_ENTITY"; + stream << "ENTITY_" << this->sceneNode->getName(); obj = (Ogre::MovableObject*)this->sceneNode->getCreator()->createEntity(stream.str(), meshName); } catch (Ogre::Exception e) @@ -171,6 +172,7 @@ void OgreVisual::AttachObject( Ogre::MovableObject *obj) { this->sceneNode->attachObject(obj); + obj->setUserObject( this ); } //////////////////////////////////////////////////////////////////////////////// @@ -524,3 +526,26 @@ this->boundingBoxNode->setVisible(false); } + +//////////////////////////////////////////////////////////////////////////////// +/// Get the entity that manages this visual +Entity *OgreVisual::GetEntity() const +{ + return this->entity; +} + +//////////////////////////////////////////////////////////////////////////////// +/// Set to true to show a white bounding box, used to indicate user selection +void OgreVisual::ShowSelectionBox( bool value ) +{ + Ogre::SceneNode *node = this->sceneNode; + + while (node && node->numAttachedObjects() == 0) + { + node = dynamic_cast<Ogre::SceneNode*>(node->getChild(0)); + } + if (node) + node->showBoundingBox(value); +} + + Modified: code/gazebo/trunk/server/rendering/OgreVisual.hh =================================================================== --- code/gazebo/trunk/server/rendering/OgreVisual.hh 2008-07-21 23:39:22 UTC (rev 6899) +++ code/gazebo/trunk/server/rendering/OgreVisual.hh 2008-07-22 16:14:59 UTC (rev 6900) @@ -38,12 +38,13 @@ { class XMLConfigNode; - + class Entity; + /// \brief Ogre Visual Object - class OgreVisual + class OgreVisual : public Ogre::UserDefinedObject { /// \brief Constructor - public: OgreVisual (OgreVisual *node); + public: OgreVisual (OgreVisual *node, Entity *owner = NULL); /// \brief Destructor public: virtual ~OgreVisual(); @@ -117,6 +118,14 @@ /// \brief Make the visual objects static renderables public: void MakeStatic(); + /// \brief Get the entity that manages this visual + public: Entity *GetEntity() const; + + /// \brief Set to true to show a white bounding box, used to indicate + // user selection + public: void ShowSelectionBox( bool value ); + + private: Ogre::MaterialPtr origMaterial; private: Ogre::MaterialPtr myMaterial; private: Ogre::SceneBlendType sceneBlendType; @@ -134,6 +143,7 @@ private: static unsigned int visualCounter; + private: Entity *entity; }; } Modified: code/gazebo/trunk/server/rendering/UserCamera.cc =================================================================== --- code/gazebo/trunk/server/rendering/UserCamera.cc 2008-07-21 23:39:22 UTC (rev 6899) +++ code/gazebo/trunk/server/rendering/UserCamera.cc 2008-07-22 16:14:59 UTC (rev 6900) @@ -39,7 +39,7 @@ //////////////////////////////////////////////////////////////////////////////// /// Constructor UserCamera::UserCamera(GLWindow *parentWindow) - : OgreCamera("User") + : OgreCamera("UserCamera") { this->window = OgreCreator::CreateWindow(parentWindow, parentWindow->w(), parentWindow->h()); Modified: code/gazebo/trunk/worlds/simpleshapes.world =================================================================== --- code/gazebo/trunk/worlds/simpleshapes.world 2008-07-21 23:39:22 UTC (rev 6899) +++ code/gazebo/trunk/worlds/simpleshapes.world 2008-07-22 16:14:59 UTC (rev 6900) @@ -15,10 +15,10 @@ <verbosity>5</verbosity> <physics:ode> - <stepTime>0.03</stepTime> + <stepTime>0.01</stepTime> <gravity>0 0 -9.8</gravity> - <cfm>0.008</cfm> - <erp>0.2</erp> + <cfm>10e-5</cfm> + <erp>0.3</erp> </physics:ode> <rendering:gui> @@ -32,18 +32,21 @@ <sky> <material>Gazebo/CloudySky</material> </sky> + <grid>false</grid> </rendering:ogre> <model:physical name="sphere1_model"> - <xyz>1 0 1.5</xyz> + <xyz>1 0 0.25</xyz> <rpy>0.0 0.0 0.0</rpy> <static>false</static> <body:sphere name="sphere1_body"> <geom:sphere name="sphere1_geom"> <size>0.5</size> - <mass>1.0</mass> + <mass>0.0</mass> + <mu1>109999.0</mu1> + <visual> <scale>0.5 0.5 0.5</scale> <mesh>unit_sphere</mesh> @@ -62,7 +65,7 @@ <geom:box name="box1_geom"> <size>1 1 1</size> - <mass>1.0</mass> + <mass>0.1</mass> <visual> <mesh>unit_box</mesh> <material>Gazebo/Rocky</material> @@ -79,6 +82,8 @@ <geom:cylinder name="cylinder1_geom"> <size>0.5 1</size> <mass>1.0</mass> + <mu1>1000.0</mu1> + <visual> <mesh>unit_cylinder</mesh> <material>Gazebo/RustyBarrel</material> @@ -100,6 +105,8 @@ <segments>10 10</segments> <uvTile>100 100</uvTile> <material>Gazebo/Grey</material> + <mu1>109999.0</mu1> + <mu2>1000.0</mu2> </geom:plane> </body:plane> </model:physical> This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. ------------------------------------------------------------------------- This SF.Net email is sponsored by the Moblin Your Move Developer's challenge Build the coolest Linux based applications with Moblin SDK & win great prizes Grand prize is a trip for two to an Open Source event anywhere in the world http://moblin-contest.org/redirect.php?banner_id=100&url=/ _______________________________________________ Playerstage-commit mailing list Playerstage-commit@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/playerstage-commit