From f04801f7cd325d0bccc733d2ddd68199ebc8e964 Mon Sep 17 00:00:00 2001 From: Armin Hornung Date: Wed, 6 Jan 2016 21:25:03 +0100 Subject: [PATCH 01/28] Changing OcTreeDataNode child array to void** => make casts more explicit and show potential memory issues (#98) --- octomap/include/octomap/OcTreeDataNode.h | 2 +- octomap/include/octomap/OcTreeDataNode.hxx | 17 +++++++++-------- octomap/src/CMakeLists.txt | 2 +- octomap/src/ColorOcTree.cpp | 4 ++-- 4 files changed, 13 insertions(+), 12 deletions(-) diff --git a/octomap/include/octomap/OcTreeDataNode.h b/octomap/include/octomap/OcTreeDataNode.h index ea208acd..2d23eb33 100644 --- a/octomap/include/octomap/OcTreeDataNode.h +++ b/octomap/include/octomap/OcTreeDataNode.h @@ -154,7 +154,7 @@ namespace octomap { void allocChildren(); /// pointer to array of children, may be NULL - OcTreeDataNode** children; + void** children; /// stored data (payload) T value; diff --git a/octomap/include/octomap/OcTreeDataNode.hxx b/octomap/include/octomap/OcTreeDataNode.hxx index 267b875b..97185634 100644 --- a/octomap/include/octomap/OcTreeDataNode.hxx +++ b/octomap/include/octomap/OcTreeDataNode.hxx @@ -55,7 +55,7 @@ namespace octomap { allocChildren(); for (unsigned i = 0; i<8; ++i){ if (rhs.children[i]) - children[i] = new OcTreeDataNode(*(rhs.children[i])); + children[i] = new OcTreeDataNode(*(static_cast*>(rhs.children[i]))); } } @@ -67,7 +67,8 @@ namespace octomap { { if (children != NULL) { for (unsigned int i=0; i<8; i++) { - if (children[i] != NULL) delete children[i]; + if (children[i] != NULL) + delete static_cast*>(children[i]); } delete[] children; } @@ -106,7 +107,7 @@ namespace octomap { void OcTreeDataNode::deleteChild(unsigned int i) { assert((i < 8) && (children != NULL)); assert(children[i] != NULL); - delete children[i]; + delete static_cast*>(children[i]); children[i] = NULL; } @@ -114,14 +115,14 @@ namespace octomap { OcTreeDataNode* OcTreeDataNode::getChild(unsigned int i) { assert((i < 8) && (children != NULL)); assert(children[i] != NULL); - return children[i]; + return static_cast* >(children[i]); } template const OcTreeDataNode* OcTreeDataNode::getChild(unsigned int i) const { assert((i < 8) && (children != NULL)); assert(children[i] != NULL); - return children[i]; + return static_cast*>(children[i]); } template @@ -168,7 +169,7 @@ namespace octomap { // delete children for (unsigned int i=0;i<8;i++) { - delete children[i]; + delete static_cast*>(children[i]); } delete[] children; children = NULL; @@ -182,7 +183,7 @@ namespace octomap { for (unsigned int k=0; k<8; k++) { createChild(k); - children[k]->setValue(value); + static_cast*>(children[k])->setValue(value); } } @@ -250,7 +251,7 @@ namespace octomap { // ============================================================ template void OcTreeDataNode::allocChildren() { - children = new OcTreeDataNode*[8]; + children = new void*[8]; for (unsigned int i=0; i<8; i++) { children[i] = NULL; } diff --git a/octomap/src/CMakeLists.txt b/octomap/src/CMakeLists.txt index e0fd2eeb..a03cd847 100644 --- a/octomap/src/CMakeLists.txt +++ b/octomap/src/CMakeLists.txt @@ -3,7 +3,7 @@ SET (octomap_SRCS AbstractOccupancyOcTree.cpp Pointcloud.cpp ScanGraph.cpp - CountingOcTree.cpp +# CountingOcTree.cpp # deactivated for now (testing) OcTree.cpp OcTreeNode.cpp OcTreeStamped.cpp diff --git a/octomap/src/ColorOcTree.cpp b/octomap/src/ColorOcTree.cpp index efd190de..3be0ffc2 100644 --- a/octomap/src/ColorOcTree.cpp +++ b/octomap/src/ColorOcTree.cpp @@ -113,7 +113,7 @@ namespace octomap { if (isColorSet()) color = getAverageChildColor(); // delete children for (unsigned int i=0;i<8;i++) { - delete children[i]; + delete static_cast(children[i]); } delete[] children; children = NULL; @@ -124,7 +124,7 @@ namespace octomap { assert(!hasChildren()); for (unsigned int k=0; k<8; k++) { createChild(k); - children[k]->setValue(value); + getChild(k)->setValue(value); getChild(k)->setColor(color); } } From 7e32ee8017dec2a1e6ed809ea56f4f4d37c63db5 Mon Sep 17 00:00:00 2001 From: Armin Hornung Date: Wed, 6 Jan 2016 21:49:30 +0100 Subject: [PATCH 02/28] First (hacky) steps for improving node subclassing (#98): createChild(), getChild(), expandNode(), pruneNode moved into OcTreeBaseImpl. OcTreeDataNode is now a friend of OcTreeBaseImpl, refactoring by removing expand and prune OcTreeDataNode. --- octomap/include/octomap/OcTreeBaseImpl.h | 33 ++++++++- octomap/include/octomap/OcTreeBaseImpl.hxx | 67 ++++++++++++++++++- octomap/include/octomap/OcTreeDataNode.h | 24 ++----- octomap/include/octomap/OcTreeDataNode.hxx | 29 -------- .../include/octomap/OccupancyOcTreeBase.hxx | 8 +-- octomap/src/octree2pointcloud.cpp | 2 +- 6 files changed, 106 insertions(+), 57 deletions(-) diff --git a/octomap/include/octomap/OcTreeBaseImpl.h b/octomap/include/octomap/OcTreeBaseImpl.h index d825e12e..c542cab7 100644 --- a/octomap/include/octomap/OcTreeBaseImpl.h +++ b/octomap/include/octomap/OcTreeBaseImpl.h @@ -108,6 +108,36 @@ namespace octomap { inline unsigned int getTreeDepth () const { return tree_depth; } inline double getNodeSize(unsigned depth) const {assert(depth <= tree_depth); return sizeLookupTable[depth];} + + + // -- Tree structure operations formerly contained in the nodes --- + + // TODO: createChild(), getChild(), getChild() const, expandNode() probelmatic => casts! + + bool createNodeChild(NODE* node, unsigned int childIdx); + + NODE* getNodeChild(NODE* node, unsigned int childIdx) const; + + const NODE* getNodeChild(const NODE* node, unsigned int childIdx) const; + + /** + * Expands a node (reverse of pruning): All children are created and + * their occupancy probability is set to the node's value. + * + * You need to verify that this is indeed a pruned node (i.e. not a + * leaf at the lowest level) + * + */ + void expandNode(NODE* node); + + /** + * Prunes a node when it is collapsible + * @return true if pruning was successful + */ + bool pruneNode(NODE* node); + + + // -------- /** * \return Pointer to the root node of the tree. This pointer @@ -464,7 +494,8 @@ namespace octomap { /// (const-parameters can't be changed) - use the copy constructor instead. OcTreeBaseImpl& operator=(const OcTreeBaseImpl&); - protected: + protected: + void allocNodeChildren(NODE* node); NODE* root; ///< Pointer to the root NODE, NULL for empty tree diff --git a/octomap/include/octomap/OcTreeBaseImpl.hxx b/octomap/include/octomap/OcTreeBaseImpl.hxx index 37e06ef6..1d9e6c81 100644 --- a/octomap/include/octomap/OcTreeBaseImpl.hxx +++ b/octomap/include/octomap/OcTreeBaseImpl.hxx @@ -171,6 +171,67 @@ namespace octomap { size_changed = true; } + + template + bool OcTreeBaseImpl::createNodeChild(NODE* node, unsigned int childIdx){ + assert(childIdx < 8); + if (node->children == NULL) { + allocNodeChildren(node); + } + assert (node.children[childIdx] == NULL); + node->children[childIdx] = new NODE(); + return true; + } + + template + NODE* OcTreeBaseImpl::getNodeChild(NODE* node, unsigned int childIdx) const{ + assert((childIdx < 8) && (node->children != NULL)); + assert(node->children[childIdx] != NULL); + return static_cast(node->children[childIdx]); + } + + template + const NODE* OcTreeBaseImpl::getNodeChild(const NODE* node, unsigned int childIdx) const{ + assert((childIdx < 8) && (node->children != NULL)); + assert(node->children[childIdx] != NULL); + return static_cast(node->children[childIdx]); + } + + template + void OcTreeBaseImpl::expandNode(NODE* node){ + assert(!node->hasChildren()); + + for (unsigned int k=0; k<8; k++) { + createNodeChild(node, k); + static_cast(node->children[k])->setValue(node->getValue()); // TODO: copy ctor for data nodes instead? + } + } + + template + bool OcTreeBaseImpl::pruneNode(NODE* node){ + + if (!node->collapsible()) + return false; + + // set value to children's values (all assumed equal) + node->setValue(node->getChild(0)->getValue()); + + // delete children + for (unsigned int i=0;i<8;i++) { + delete static_cast(node->children[i]); + } + delete[] node->children; + node->children = NULL; + + return true; + } + + template + void OcTreeBaseImpl::allocNodeChildren(NODE* node){ + node->allocChildren(); // TODO move here? + } + + template inline unsigned short int OcTreeBaseImpl::coordToKey(double coordinate, unsigned depth) const{ @@ -552,7 +613,7 @@ namespace octomap { if ((!node->hasChildren()) && (node != this->root)) { // current node does not have children AND it's not the root node // -> expand pruned node - node->expandNode(); + expandNode(node); this->tree_size+=8; this->size_changed = true; } else { // no branch here, node does not exist @@ -594,7 +655,7 @@ namespace octomap { else { // max level reached - if (node->pruneNode()) { + if (pruneNode(node)) { num_pruned++; tree_size -= 8; size_changed = true; @@ -613,7 +674,7 @@ namespace octomap { // current node has no children => can be expanded if (!node->hasChildren()){ - node->expandNode(); + expandNode(node); tree_size +=8; size_changed = true; } diff --git a/octomap/include/octomap/OcTreeDataNode.h b/octomap/include/octomap/OcTreeDataNode.h index 2d23eb33..5e959c03 100644 --- a/octomap/include/octomap/OcTreeDataNode.h +++ b/octomap/include/octomap/OcTreeDataNode.h @@ -45,6 +45,9 @@ namespace octomap { }; + + // forward declaration for friend in OcTreeDataNode + template class OcTreeBaseImpl; /** * Basic node in the OcTree that can hold arbitrary data of type T in value. @@ -59,6 +62,8 @@ namespace octomap { * See ColorOcTreeNode in ColorOcTree.h for an example. */ template class OcTreeDataNode: public AbstractOcTreeNode { + template + friend class OcTreeBaseImpl; public: @@ -100,25 +105,6 @@ namespace octomap { /// Deletes the i-th child of the node void deleteChild(unsigned int i); - // -- pruning of children ----------------------- - - - /** - * Prunes a node when it is collapsible - * @return true if pruning was successful - */ - bool pruneNode(); - - /** - * Expands a node (reverse of pruning): All children are created and - * their occupancy probability is set to the node's value. - * - * You need to verify that this is indeed a pruned node (i.e. not a - * leaf at the lowest level) - * - */ - void expandNode(); - /// @return value stored in the node T getValue() const{return value;}; /// sets value to be stored in the node diff --git a/octomap/include/octomap/OcTreeDataNode.hxx b/octomap/include/octomap/OcTreeDataNode.hxx index 97185634..d2ccdb96 100644 --- a/octomap/include/octomap/OcTreeDataNode.hxx +++ b/octomap/include/octomap/OcTreeDataNode.hxx @@ -158,35 +158,6 @@ namespace octomap { return true; } - template - bool OcTreeDataNode::pruneNode() { - - if (!this->collapsible()) - return false; - - // set value to children's values (all assumed equal) - setValue(getChild(0)->getValue()); - - // delete children - for (unsigned int i=0;i<8;i++) { - delete static_cast*>(children[i]); - } - delete[] children; - children = NULL; - - return true; - } - - template - void OcTreeDataNode::expandNode() { - assert(!hasChildren()); - - for (unsigned int k=0; k<8; k++) { - createChild(k); - static_cast*>(children[k])->setValue(value); - } - } - // ============================================================ // = File IO ======================================= // ============================================================ diff --git a/octomap/include/octomap/OccupancyOcTreeBase.hxx b/octomap/include/octomap/OccupancyOcTreeBase.hxx index 91e49972..8da13203 100644 --- a/octomap/include/octomap/OccupancyOcTreeBase.hxx +++ b/octomap/include/octomap/OccupancyOcTreeBase.hxx @@ -378,7 +378,7 @@ namespace octomap { if ((!node->hasChildren()) && !node_just_created ) { // current node does not have children AND it is not a new node // -> expand pruned node - node->expandNode(); + this->expandNode(node); this->tree_size+=8; this->size_changed = true; } @@ -397,7 +397,7 @@ namespace octomap { NODE* retval = updateNodeRecurs(node->getChild(pos), created_node, key, depth+1, log_odds_update, lazy_eval); // prune node if possible, otherwise set own probability // note: combining both did not lead to a speedup! - if (node->pruneNode()){ + if (this->pruneNode(node)){ this->tree_size -= 8; // return pointer to current parent (pruned), the just updated node no longer exists retval = node; @@ -447,7 +447,7 @@ namespace octomap { if ((!node->hasChildren()) && !node_just_created ) { // current node does not have children AND it is not a new node // -> expand pruned node - node->expandNode(); + this->expandNode(node); this->tree_size+=8; this->size_changed = true; } @@ -466,7 +466,7 @@ namespace octomap { NODE* retval = setNodeValueRecurs(node->getChild(pos), created_node, key, depth+1, log_odds_value, lazy_eval); // prune node if possible, otherwise set own probability // note: combining both did not lead to a speedup! - if (node->pruneNode()){ + if (this->pruneNode(node)){ this->tree_size -= 8; // return pointer to current parent (pruned), the just updated node no longer exists retval = node; diff --git a/octomap/src/octree2pointcloud.cpp b/octomap/src/octree2pointcloud.cpp index e971609c..c74bbcd4 100644 --- a/octomap/src/octree2pointcloud.cpp +++ b/octomap/src/octree2pointcloud.cpp @@ -78,7 +78,7 @@ int main(int argc, char** argv) { } for (vector::iterator it = collapsed_occ_nodes.begin(); it != collapsed_occ_nodes.end(); ++it) { - (*it)->expandNode(); + tree->expandNode(*it); } cout << "expanded " << collapsed_occ_nodes.size() << " nodes" << endl; } while(collapsed_occ_nodes.size() > 0); From 4223d9ada8d773869f29b15b6b15e1b117c03cbc Mon Sep 17 00:00:00 2001 From: Armin Hornung Date: Wed, 6 Jan 2016 22:08:06 +0100 Subject: [PATCH 03/28] Moving deleteChild() from OcTreeDataNode into OcTreeBaseImpl --- octomap/include/octomap/OcTreeBaseImpl.h | 8 +++++--- octomap/include/octomap/OcTreeBaseImpl.hxx | 10 +++++++++- octomap/include/octomap/OcTreeDataNode.h | 5 +---- octomap/include/octomap/OcTreeDataNode.hxx | 11 ++--------- 4 files changed, 17 insertions(+), 17 deletions(-) diff --git a/octomap/include/octomap/OcTreeBaseImpl.h b/octomap/include/octomap/OcTreeBaseImpl.h index c542cab7..1bc31651 100644 --- a/octomap/include/octomap/OcTreeBaseImpl.h +++ b/octomap/include/octomap/OcTreeBaseImpl.h @@ -111,11 +111,13 @@ namespace octomap { // -- Tree structure operations formerly contained in the nodes --- - - // TODO: createChild(), getChild(), getChild() const, expandNode() probelmatic => casts! - + + /// Creates (allocates) the i-th child of the node bool createNodeChild(NODE* node, unsigned int childIdx); + /// Deletes the i-th child of the node + void deleteNodeChild(NODE* node, unsigned int childIdx); + NODE* getNodeChild(NODE* node, unsigned int childIdx) const; const NODE* getNodeChild(const NODE* node, unsigned int childIdx) const; diff --git a/octomap/include/octomap/OcTreeBaseImpl.hxx b/octomap/include/octomap/OcTreeBaseImpl.hxx index 1d9e6c81..949c3887 100644 --- a/octomap/include/octomap/OcTreeBaseImpl.hxx +++ b/octomap/include/octomap/OcTreeBaseImpl.hxx @@ -183,6 +183,14 @@ namespace octomap { return true; } + template + void OcTreeBaseImpl::deleteNodeChild(NODE* node, unsigned int childIdx){ + assert((childIdx < 8) && (node->children != NULL)); + assert(node->children[childIdx] != NULL); + delete static_cast(node->children[childIdx]); + node->children[childIdx] = NULL; + } + template NODE* OcTreeBaseImpl::getNodeChild(NODE* node, unsigned int childIdx) const{ assert((childIdx < 8) && (node->children != NULL)); @@ -625,7 +633,7 @@ namespace octomap { bool deleteChild = deleteNodeRecurs(node->getChild(pos), depth+1, max_depth, key); if (deleteChild){ // TODO: lazy eval? - node->deleteChild(pos); + this->deleteNodeChild(node, pos); this->tree_size-=1; this->size_changed = true; if (!node->hasChildren()) diff --git a/octomap/include/octomap/OcTreeDataNode.h b/octomap/include/octomap/OcTreeDataNode.h index 5e959c03..140b5149 100644 --- a/octomap/include/octomap/OcTreeDataNode.h +++ b/octomap/include/octomap/OcTreeDataNode.h @@ -82,7 +82,7 @@ namespace octomap { /// initialize i-th child, allocate children array if needed - bool createChild(unsigned int i); + bool createChild(unsigned int i); // TODO: only used by read in here => move /// Safe test to check of the i-th child exists, /// first tests if there are any children. @@ -102,9 +102,6 @@ namespace octomap { /// and have the same occupancy value bool collapsible() const; - /// Deletes the i-th child of the node - void deleteChild(unsigned int i); - /// @return value stored in the node T getValue() const{return value;}; /// sets value to be stored in the node diff --git a/octomap/include/octomap/OcTreeDataNode.hxx b/octomap/include/octomap/OcTreeDataNode.hxx index d2ccdb96..4009b68e 100644 --- a/octomap/include/octomap/OcTreeDataNode.hxx +++ b/octomap/include/octomap/OcTreeDataNode.hxx @@ -68,8 +68,9 @@ namespace octomap { if (children != NULL) { for (unsigned int i=0; i<8; i++) { if (children[i] != NULL) - delete static_cast*>(children[i]); + delete static_cast*>(children[i]); } + // TODO: ensure correct destructor is called for each derived node! delete[] children; } @@ -103,14 +104,6 @@ namespace octomap { return false; } - template - void OcTreeDataNode::deleteChild(unsigned int i) { - assert((i < 8) && (children != NULL)); - assert(children[i] != NULL); - delete static_cast*>(children[i]); - children[i] = NULL; - } - template OcTreeDataNode* OcTreeDataNode::getChild(unsigned int i) { assert((i < 8) && (children != NULL)); From b843feee998391118d489dde136f7ee216c5c4f3 Mon Sep 17 00:00:00 2001 From: Armin Hornung Date: Fri, 8 Jan 2016 13:29:29 +0100 Subject: [PATCH 04/28] Refactoring: moving recursive read/write and createChild from nodes into OcTreeBaseImpl. Nodes now only (de)seralize their payload in read/writeData. --- octomap/include/octomap/ColorOcTree.h | 5 +- octomap/include/octomap/OcTreeBaseImpl.h | 14 ++++- octomap/include/octomap/OcTreeBaseImpl.hxx | 69 +++++++++++++++++++--- octomap/include/octomap/OcTreeDataNode.h | 28 ++------- octomap/include/octomap/OcTreeDataNode.hxx | 54 +---------------- octomap/src/ColorOcTree.cpp | 32 ++-------- octomap/src/testing/test_io.cpp | 8 ++- 7 files changed, 94 insertions(+), 116 deletions(-) diff --git a/octomap/include/octomap/ColorOcTree.h b/octomap/include/octomap/ColorOcTree.h index 9830a116..757fc951 100644 --- a/octomap/include/octomap/ColorOcTree.h +++ b/octomap/include/octomap/ColorOcTree.h @@ -82,6 +82,7 @@ namespace octomap { return true; } + // TODO: move into tree! bool pruneNode(); void expandNode(); @@ -104,8 +105,8 @@ namespace octomap { ColorOcTreeNode::Color getAverageChildColor() const; // file I/O - std::istream& readValue (std::istream &s); - std::ostream& writeValue(std::ostream &s) const; + std::istream& readData(std::istream &s); + std::ostream& writeData(std::ostream &s) const; protected: Color color; diff --git a/octomap/include/octomap/OcTreeBaseImpl.h b/octomap/include/octomap/OcTreeBaseImpl.h index 1bc31651..fea58cc3 100644 --- a/octomap/include/octomap/OcTreeBaseImpl.h +++ b/octomap/include/octomap/OcTreeBaseImpl.h @@ -39,7 +39,7 @@ #include #include #include - +#include #include "octomap_types.h" #include "OcTreeKey.h" @@ -112,14 +112,16 @@ namespace octomap { // -- Tree structure operations formerly contained in the nodes --- - /// Creates (allocates) the i-th child of the node - bool createNodeChild(NODE* node, unsigned int childIdx); + /// Creates (allocates) the i-th child of the node. @return ptr to newly create NODE + NODE* createNodeChild(NODE* node, unsigned int childIdx); /// Deletes the i-th child of the node void deleteNodeChild(NODE* node, unsigned int childIdx); + /// @return ptr to child number childIdx of node NODE* getNodeChild(NODE* node, unsigned int childIdx) const; + /// @return const ptr to child number childIdx of node const NODE* getNodeChild(const NODE* node, unsigned int childIdx) const; /** @@ -479,6 +481,12 @@ namespace octomap { void calcMinMax(); void calcNumNodesRecurs(NODE* node, size_t& num_nodes) const; + + /// recursive call of readData() + std::istream& readNodesRecurs(NODE*, std::istream &s); + + /// recursive call of writeData() + std::ostream& writeNodesRecurs(const NODE*, std::ostream &s) const; /// recursive call of deleteNode() bool deleteNodeRecurs(NODE* node, unsigned int depth, unsigned int max_depth, const OcTreeKey& key); diff --git a/octomap/include/octomap/OcTreeBaseImpl.hxx b/octomap/include/octomap/OcTreeBaseImpl.hxx index 949c3887..ac20e38f 100644 --- a/octomap/include/octomap/OcTreeBaseImpl.hxx +++ b/octomap/include/octomap/OcTreeBaseImpl.hxx @@ -173,14 +173,15 @@ namespace octomap { } template - bool OcTreeBaseImpl::createNodeChild(NODE* node, unsigned int childIdx){ + NODE* OcTreeBaseImpl::createNodeChild(NODE* node, unsigned int childIdx){ assert(childIdx < 8); if (node->children == NULL) { allocNodeChildren(node); } assert (node.children[childIdx] == NULL); - node->children[childIdx] = new NODE(); - return true; + NODE* newNode = new NODE(); + node->children[childIdx] = static_cast(newNode); + return newNode; } template @@ -210,8 +211,8 @@ namespace octomap { assert(!node->hasChildren()); for (unsigned int k=0; k<8; k++) { - createNodeChild(node, k); - static_cast(node->children[k])->setValue(node->getValue()); // TODO: copy ctor for data nodes instead? + NODE* newNode = createNodeChild(node, k); + newNode->setValue(node->getValue()); // TODO: copy ctor for data nodes instead? } } @@ -698,8 +699,38 @@ namespace octomap { template std::ostream& OcTreeBaseImpl::writeData(std::ostream &s) const{ if (root) - root->writeValue(s); + writeNodesRecurs(root, s); + + return s; + } + + template + std::ostream& OcTreeBaseImpl::writeNodesRecurs(const NODE* node, std::ostream &s) const{ + node->writeData(s); + + // 1 bit for each children; 0: empty, 1: allocated + std::bitset<8> children; + for (unsigned int i=0; i<8; i++) { + if (node->childExists(i)) + children[i] = 1; + else + children[i] = 0; + } + + char children_char = (char) children.to_ulong(); + s.write((char*)&children_char, sizeof(char)); + +// std::cout << "wrote: " << value << " " +// << children.to_string,std::allocator >() +// << std::endl; + // recursively write children + for (unsigned int i=0; i<8; i++) { + if (children[i] == 1) { + this->writeNodesRecurs(getNodeChild(node, i), s); + } + } + return s; } @@ -720,10 +751,34 @@ namespace octomap { } root = new NODE(); - root->readValue(s); + readNodesRecurs(root, s); + tree_size = calcNumNodes(); // compute number of nodes return s; } + + template + std::istream& OcTreeBaseImpl::readNodesRecurs(NODE* node, std::istream &s) { + + node->readData(s); + + char children_char; + s.read((char*)&children_char, sizeof(char)); + std::bitset<8> children ((unsigned long long) children_char); + + //std::cout << "read: " << node->getValue() << " " + // << children.to_string,std::allocator >() + // << std::endl; + + for (unsigned int i=0; i<8; i++) { + if (children[i] == 1){ + NODE* newNode = createNodeChild(node, i); + readNodesRecurs(newNode, s); + } + } + + return s; + } diff --git a/octomap/include/octomap/OcTreeDataNode.h b/octomap/include/octomap/OcTreeDataNode.h index 140b5149..84f43a00 100644 --- a/octomap/include/octomap/OcTreeDataNode.h +++ b/octomap/include/octomap/OcTreeDataNode.h @@ -37,7 +37,6 @@ #include "octomap_types.h" #include "assert.h" -#include namespace octomap { @@ -80,10 +79,6 @@ namespace octomap { // -- children ---------------------------------- - - /// initialize i-th child, allocate children array if needed - bool createChild(unsigned int i); // TODO: only used by read in here => move - /// Safe test to check of the i-th child exists, /// first tests if there are any children. /// \return true if the i-th child exists @@ -109,24 +104,11 @@ namespace octomap { // file IO: - /** - * Read node from binary stream (incl. float value), - * recursively continue with all children. - * - * @param s - * @return - */ - std::istream& readValue(std::istream &s); - - /** - * Write node to binary stream (incl float value), - * recursively continue with all children. - * This preserves the complete state of the node. - * - * @param s - * @return - */ - std::ostream& writeValue(std::ostream &s) const; + /// Read node payload (data only) from binary stream + std::istream& readData(std::istream &s); + + /// Write node payload (data only) to binary stream + std::ostream& writeData(std::ostream &s) const; /// Make the templated data type available from the outside diff --git a/octomap/include/octomap/OcTreeDataNode.hxx b/octomap/include/octomap/OcTreeDataNode.hxx index 4009b68e..061e9b1b 100644 --- a/octomap/include/octomap/OcTreeDataNode.hxx +++ b/octomap/include/octomap/OcTreeDataNode.hxx @@ -85,15 +85,6 @@ namespace octomap { // = children ======================================= // ============================================================ - template - bool OcTreeDataNode::createChild(unsigned int i) { - if (children == NULL) { - allocChildren(); - } - assert (children[i] == NULL); - children[i] = new OcTreeDataNode(); - return true; - } template bool OcTreeDataNode::childExists(unsigned int i) const { @@ -156,56 +147,15 @@ namespace octomap { // ============================================================ template - std::istream& OcTreeDataNode::readValue(std::istream &s) { - - char children_char; - - // read data: + std::istream& OcTreeDataNode::readData(std::istream &s) { s.read((char*) &value, sizeof(value)); - s.read((char*)&children_char, sizeof(char)); - std::bitset<8> children ((unsigned long long) children_char); - - // std::cout << "read: " << value << " " - // << children.to_string,std::allocator >() - // << std::endl; - - for (unsigned int i=0; i<8; i++) { - if (children[i] == 1){ - createChild(i); - getChild(i)->readValue(s); - } - } return s; } template - std::ostream& OcTreeDataNode::writeValue(std::ostream &s) const{ - - // 1 bit for each children; 0: empty, 1: allocated - std::bitset<8> children; - - for (unsigned int i=0; i<8; i++) { - if (childExists(i)) - children[i] = 1; - else - children[i] = 0; - } - - char children_char = (char) children.to_ulong(); + std::ostream& OcTreeDataNode::writeData(std::ostream &s) const{ s.write((const char*) &value, sizeof(value)); - s.write((char*)&children_char, sizeof(char)); - - // std::cout << "wrote: " << value << " " - // << children.to_string,std::allocator >() - // << std::endl; - - // write children's children - for (unsigned int i=0; i<8; i++) { - if (children[i] == 1) { - this->getChild(i)->writeValue(s); - } - } return s; } diff --git a/octomap/src/ColorOcTree.cpp b/octomap/src/ColorOcTree.cpp index 3be0ffc2..b8857fa0 100644 --- a/octomap/src/ColorOcTree.cpp +++ b/octomap/src/ColorOcTree.cpp @@ -37,41 +37,17 @@ namespace octomap { // node implementation -------------------------------------- - std::ostream& ColorOcTreeNode::writeValue (std::ostream &s) const { - // 1 bit for each children; 0: empty, 1: allocated - std::bitset<8> children; - for (unsigned int i=0; i<8; i++) { - if (childExists(i)) children[i] = 1; - else children[i] = 0; - } - char children_char = (char) children.to_ulong(); - - // write node data + std::ostream& ColorOcTreeNode::writeData(std::ostream &s) const { s.write((const char*) &value, sizeof(value)); // occupancy s.write((const char*) &color, sizeof(Color)); // color - s.write((char*)&children_char, sizeof(char)); // child existence - - // write existing children - for (unsigned int i=0; i<8; ++i) - if (children[i] == 1) this->getChild(i)->writeValue(s); + return s; } - std::istream& ColorOcTreeNode::readValue (std::istream &s) { - // read node data - char children_char; + std::istream& ColorOcTreeNode::readData(std::istream &s) { s.read((char*) &value, sizeof(value)); // occupancy s.read((char*) &color, sizeof(Color)); // color - s.read((char*)&children_char, sizeof(char)); // child existence - - // read existing children - std::bitset<8> children ((unsigned long long) children_char); - for (unsigned int i=0; i<8; i++) { - if (children[i] == 1){ - createChild(i); - getChild(i)->readValue(s); - } - } + return s; } diff --git a/octomap/src/testing/test_io.cpp b/octomap/src/testing/test_io.cpp index a5625736..031ff9e3 100644 --- a/octomap/src/testing/test_io.cpp +++ b/octomap/src/testing/test_io.cpp @@ -17,6 +17,7 @@ int main(int argc, char** argv) { return 1; // exit 1 means failure } + std::cout << "Testing empty OcTree...\n"; //empty tree OcTree emptyTree(0.999); EXPECT_EQ(emptyTree.size(), 0); @@ -34,6 +35,7 @@ int main(int argc, char** argv) { + std::cout << "Testing reference OcTree from file ...\n"; string filename = string(argv[1]); string filenameOt = "test_io_file.ot"; @@ -44,6 +46,7 @@ int main(int argc, char** argv) { OcTree tree (0.1); EXPECT_TRUE (tree.readBinary(filename)); + std::cout << " Copy Constructor / assignment / ==\n"; // test copy constructor / assignment: OcTree* treeCopy = new OcTree(tree); EXPECT_TRUE(tree == *treeCopy); @@ -68,6 +71,7 @@ int main(int argc, char** argv) { delete treeCopy; + std::cout << " Swap\n"; // test swap: OcTree emptyT(tree.getResolution()); OcTree emptySw(emptyT); @@ -84,9 +88,10 @@ int main(int argc, char** argv) { EXPECT_TRUE(readTreeBt.readBinary(filenameBtOut)); EXPECT_TRUE(tree == readTreeBt); + std::cout <<" Write to .ot / read through AbstractOcTree\n"; // now write to .ot, read & compare EXPECT_TRUE(tree.write(filenameOt)); - + AbstractOcTree* readTreeAbstract = AbstractOcTree::read(filenameOt); EXPECT_TRUE(readTreeAbstract); @@ -105,6 +110,7 @@ int main(int argc, char** argv) { EXPECT_FALSE(tree == *readTreeOt); // simple test for tree headers (color) + std::cout << "Testing ColorOcTree...\n"; double res = 0.02; std::string filenameColor = "test_io_color_file.ot"; ColorOcTree colorTree(res); From a703611d70b711d976abcf9ca1d57778190336f9 Mon Sep 17 00:00:00 2001 From: Armin Hornung Date: Fri, 8 Jan 2016 20:37:48 +0100 Subject: [PATCH 05/28] Refactoring: Moving isCollapsible() and getChild() from nodes into OcTreeBaseImpl --- octomap/include/octomap/ColorOcTree.h | 5 +- octomap/include/octomap/CountingOcTree.h | 16 +----- octomap/include/octomap/OcTreeBaseImpl.h | 4 ++ octomap/include/octomap/OcTreeBaseImpl.hxx | 39 +++++++++++---- octomap/include/octomap/OcTreeDataNode.h | 10 ---- octomap/include/octomap/OcTreeDataNode.hxx | 36 +------------ octomap/include/octomap/OcTreeIterator.hxx | 16 +++--- octomap/include/octomap/OcTreeNode.h | 11 +--- octomap/include/octomap/OcTreeStamped.h | 18 +------ octomap/include/octomap/OccupancyOcTreeBase.h | 2 +- .../include/octomap/OccupancyOcTreeBase.hxx | 50 +++++++++---------- octomap/src/ColorOcTree.cpp | 18 +++++-- octomap/src/CountingOcTree.cpp | 11 +--- octomap/src/OcTreeNode.cpp | 17 ++----- octomap/src/testing/test_iterators.cpp | 12 ++--- 15 files changed, 101 insertions(+), 164 deletions(-) diff --git a/octomap/include/octomap/ColorOcTree.h b/octomap/include/octomap/ColorOcTree.h index 757fc951..1372a8d1 100644 --- a/octomap/include/octomap/ColorOcTree.h +++ b/octomap/include/octomap/ColorOcTree.h @@ -69,11 +69,12 @@ namespace octomap { } // children + //TODO remove inline ColorOcTreeNode* getChild(unsigned int i) { - return static_cast (OcTreeNode::getChild(i)); + return static_cast (children[i]); } inline const ColorOcTreeNode* getChild(unsigned int i) const { - return static_cast (OcTreeNode::getChild(i)); + return static_cast (children[i]); } bool createChild(unsigned int i) { diff --git a/octomap/include/octomap/CountingOcTree.h b/octomap/include/octomap/CountingOcTree.h index 9524ed95..1f687c6e 100644 --- a/octomap/include/octomap/CountingOcTree.h +++ b/octomap/include/octomap/CountingOcTree.h @@ -56,22 +56,11 @@ namespace octomap { CountingOcTreeNode(); ~CountingOcTreeNode(); - bool createChild(unsigned int i); - - inline CountingOcTreeNode* getChild(unsigned int i) { - return static_cast (OcTreeDataNode::getChild(i)); - } - - inline const CountingOcTreeNode* getChild(unsigned int i) const { - return static_cast (OcTreeDataNode::getChild(i)); - } - + inline unsigned int getCount() const { return getValue(); } inline void increaseCount() { value++; } inline void setCount(unsigned c) {this->setValue(c); } - // overloaded: - void expandNode(); }; @@ -82,8 +71,7 @@ namespace octomap { * Count is recursive, parent nodes have the summed count of their * children. * - * \note In our mapping system this data structure is used in - * the sensor model only. Do not use, e.g., insertScan. + * \note Was only used internally, not used anymore */ class CountingOcTree : public OcTreeBase { diff --git a/octomap/include/octomap/OcTreeBaseImpl.h b/octomap/include/octomap/OcTreeBaseImpl.h index fea58cc3..95204b6e 100644 --- a/octomap/include/octomap/OcTreeBaseImpl.h +++ b/octomap/include/octomap/OcTreeBaseImpl.h @@ -124,6 +124,10 @@ namespace octomap { /// @return const ptr to child number childIdx of node const NODE* getNodeChild(const NODE* node, unsigned int childIdx) const; + /// A node is collapsible if all children exist, don't have children of their own + /// and have the same occupancy value + bool isNodeCollapsible(const NODE* node) const; + /** * Expands a node (reverse of pruning): All children are created and * their occupancy probability is set to the node's value. diff --git a/octomap/include/octomap/OcTreeBaseImpl.hxx b/octomap/include/octomap/OcTreeBaseImpl.hxx index ac20e38f..d920fab3 100644 --- a/octomap/include/octomap/OcTreeBaseImpl.hxx +++ b/octomap/include/octomap/OcTreeBaseImpl.hxx @@ -205,6 +205,27 @@ namespace octomap { assert(node->children[childIdx] != NULL); return static_cast(node->children[childIdx]); } + + template + bool OcTreeBaseImpl::isNodeCollapsible(const NODE* node) const{ + // all children must exist, must not have children of + // their own and have the same occupancy probability + if (!node->childExists(0)) + return false; + + const NODE* firstChild = getNodeChild(node, 0); + if (firstChild->hasChildren()) + return false; + + for (unsigned int i = 1; i<8; i++) { + // comparison via getChild so that casts of derived classes ensure + // that the right == operator gets called + if (!node->childExists(i) || getNodeChild(node, i)->hasChildren() || !(*(getNodeChild(node, i)) == *(firstChild))) + return false; + } + + return true; + } template void OcTreeBaseImpl::expandNode(NODE* node){ @@ -219,11 +240,11 @@ namespace octomap { template bool OcTreeBaseImpl::pruneNode(NODE* node){ - if (!node->collapsible()) + if (!isNodeCollapsible(node)) return false; // set value to children's values (all assumed equal) - node->setValue(node->getChild(0)->getValue()); + node->setValue(getNodeChild(node, 0)->getValue()); // delete children for (unsigned int i=0;i<8;i++) { @@ -404,7 +425,7 @@ namespace octomap { unsigned int pos = computeChildIdx(key_at_depth, i); if (curNode->childExists(pos)) { // cast needed: (nodes need to ensure it's the right pointer) - curNode = static_cast( curNode->getChild(pos) ); + curNode = getNodeChild(curNode, pos); } else { // we expected a child but did not get it // is the current node a leaf already? @@ -631,7 +652,7 @@ namespace octomap { } // follow down further, fix inner nodes on way back up - bool deleteChild = deleteNodeRecurs(node->getChild(pos), depth+1, max_depth, key); + bool deleteChild = deleteNodeRecurs(getNodeChild(node, pos), depth+1, max_depth, key); if (deleteChild){ // TODO: lazy eval? this->deleteNodeChild(node, pos); @@ -640,7 +661,7 @@ namespace octomap { if (!node->hasChildren()) return true; else{ - node->updateOccupancyChildren(); + node->updateOccupancyChildren(); // TODO: occupancy? } } // node did not lose a child, or still has other children @@ -657,7 +678,7 @@ namespace octomap { if (depth < max_depth) { for (unsigned int i=0; i<8; i++) { if (node->childExists(i)) { - pruneRecurs(node->getChild(i), depth+1, max_depth, num_pruned); + pruneRecurs(getNodeChild(node, i), depth+1, max_depth, num_pruned); } } } // end if depth @@ -690,7 +711,7 @@ namespace octomap { // recursively expand children for (unsigned int i=0; i<8; i++) { if (node->childExists(i)) { - expandRecurs(node->getChild(i), depth+1, max_depth); + expandRecurs(getNodeChild(node, i), depth+1, max_depth); } } } @@ -966,7 +987,7 @@ namespace octomap { for (unsigned int i=0; i<8; ++i) { if (node->childExists(i)) { num_nodes++; - calcNumNodesRecurs(node->getChild(i), num_nodes); + calcNumNodesRecurs(getNodeChild(node, i), num_nodes); } } } @@ -1035,7 +1056,7 @@ namespace octomap { size_t sum_leafs_children = 0; for (unsigned int i=0; i<8; ++i) { if (parent->childExists(i)) { - sum_leafs_children += getNumLeafNodesRecurs(parent->getChild(i)); + sum_leafs_children += getNumLeafNodesRecurs(getNodeChild(parent, i)); } } return sum_leafs_children; diff --git a/octomap/include/octomap/OcTreeDataNode.h b/octomap/include/octomap/OcTreeDataNode.h index 84f43a00..7cce9e7d 100644 --- a/octomap/include/octomap/OcTreeDataNode.h +++ b/octomap/include/octomap/OcTreeDataNode.h @@ -84,19 +84,9 @@ namespace octomap { /// \return true if the i-th child exists bool childExists(unsigned int i) const; - /// \return a pointer to the i-th child of the node. The child needs to exist. - OcTreeDataNode* getChild(unsigned int i); - - /// \return a const pointer to the i-th child of the node. The child needs to exist. - const OcTreeDataNode* getChild(unsigned int i) const; - /// \return true if the node has at least one child bool hasChildren() const; - /// A node is collapsible if all children exist, don't have children of their own - /// and have the same occupancy value - bool collapsible() const; - /// @return value stored in the node T getValue() const{return value;}; /// sets value to be stored in the node diff --git a/octomap/include/octomap/OcTreeDataNode.hxx b/octomap/include/octomap/OcTreeDataNode.hxx index 061e9b1b..51e37374 100644 --- a/octomap/include/octomap/OcTreeDataNode.hxx +++ b/octomap/include/octomap/OcTreeDataNode.hxx @@ -94,21 +94,7 @@ namespace octomap { else return false; } - - template - OcTreeDataNode* OcTreeDataNode::getChild(unsigned int i) { - assert((i < 8) && (children != NULL)); - assert(children[i] != NULL); - return static_cast* >(children[i]); - } - - template - const OcTreeDataNode* OcTreeDataNode::getChild(unsigned int i) const { - assert((i < 8) && (children != NULL)); - assert(children[i] != NULL); - return static_cast*>(children[i]); - } - + template bool OcTreeDataNode::hasChildren() const { if (children == NULL) @@ -121,26 +107,6 @@ namespace octomap { return false; } - // ============================================================ - // = pruning ======================================= - // ============================================================ - - - template - bool OcTreeDataNode::collapsible() const { - // all children must exist, must not have children of - // their own and have the same occupancy probability - if (!childExists(0) || getChild(0)->hasChildren()) - return false; - - for (unsigned int i = 1; i<8; i++) { - // comparison via getChild so that casts of derived classes ensure - // that the right == operator gets called - if (!childExists(i) || getChild(i)->hasChildren() || !(*(getChild(i)) == *(getChild(0)))) - return false; - } - return true; - } // ============================================================ // = File IO ======================================= diff --git a/octomap/include/octomap/OcTreeIterator.hxx b/octomap/include/octomap/OcTreeIterator.hxx index 6a2fd5ed..7a018fe4 100644 --- a/octomap/include/octomap/OcTreeIterator.hxx +++ b/octomap/include/octomap/OcTreeIterator.hxx @@ -154,6 +154,12 @@ protected: + OcTreeBaseImpl const* tree; ///< Octree this iterator is working on + unsigned char maxDepth; ///< Maximum depth for depth-limited queries + + /// Internal recursion stack. Apparently a stack of vector works fastest here. + std::stack > stack; + /// One step of depth-first tree traversal. /// How this is used depends on the actual iterator. void singleIncrement(){ @@ -170,7 +176,7 @@ for (int i=7; i>=0; --i) { if (top.node->childExists(i)) { computeChildKey(i, center_offset_key, top.key, s.key); - s.node = top.node->getChild(i); + s.node = tree->getNodeChild(top.node, i); //OCTOMAP_DEBUG_STR("Current depth: " << int(top.depth) << " new: "<< int(s.depth) << " child#" << i <<" ptr: "< const* tree; ///< Octree this iterator is working on - unsigned char maxDepth; ///< Maximum depth for depth-limited queries - - /// Internal recursion stack. Apparently a stack of vector works fastest here. - std::stack > stack; - }; /** @@ -439,7 +439,7 @@ && (minKey[1] <= (s.key[1] + center_offset_key)) && (maxKey[1] >= (s.key[1] - center_offset_key)) && (minKey[2] <= (s.key[2] + center_offset_key)) && (maxKey[2] >= (s.key[2] - center_offset_key))) { - s.node = top.node->getChild(i); + s.node = this->tree->getNodeChild(top.node, i); this->stack.push(s); assert(s.depth <= this->maxDepth); } diff --git a/octomap/include/octomap/OcTreeNode.h b/octomap/include/octomap/OcTreeNode.h index 4236765d..39fff598 100644 --- a/octomap/include/octomap/OcTreeNode.h +++ b/octomap/include/octomap/OcTreeNode.h @@ -58,16 +58,7 @@ namespace octomap { OcTreeNode(); ~OcTreeNode(); - bool createChild(unsigned int i); - - // overloaded, so that the return type is correct: - inline OcTreeNode* getChild(unsigned int i) { - return static_cast (OcTreeDataNode::getChild(i)); - } - inline const OcTreeNode* getChild(unsigned int i) const { - return static_cast (OcTreeDataNode::getChild(i)); - } - + // -- node occupancy ---------------------------- /// \return occupancy probability of node diff --git a/octomap/include/octomap/OcTreeStamped.h b/octomap/include/octomap/OcTreeStamped.h index 278a1791..86e925ae 100644 --- a/octomap/include/octomap/OcTreeStamped.h +++ b/octomap/include/octomap/OcTreeStamped.h @@ -51,22 +51,8 @@ namespace octomap { bool operator==(const OcTreeNodeStamped& rhs) const{ return (rhs.value == value && rhs.timestamp == timestamp); - } - - // children - inline OcTreeNodeStamped* getChild(unsigned int i) { - return static_cast (OcTreeNode::getChild(i)); - } - inline const OcTreeNodeStamped* getChild(unsigned int i) const { - return static_cast (OcTreeNode::getChild(i)); - } - - bool createChild(unsigned int i) { - if (children == NULL) allocChildren(); - children[i] = new OcTreeNodeStamped(); - return true; - } - + } + // timestamp inline unsigned int getTimestamp() const { return timestamp; } inline void updateTimestamp() { timestamp = (unsigned int) time(NULL);} diff --git a/octomap/include/octomap/OccupancyOcTreeBase.h b/octomap/include/octomap/OccupancyOcTreeBase.h index 342a5fe3..22675907 100644 --- a/octomap/include/octomap/OccupancyOcTreeBase.h +++ b/octomap/include/octomap/OccupancyOcTreeBase.h @@ -444,7 +444,7 @@ namespace octomap { * This will set the log_odds_occupancy value of * all leaves to either free or occupied. */ - std::istream& readBinaryNode(std::istream &s, NODE* node) const; + std::istream& readBinaryNode(std::istream &s, NODE* node); /** * Write node to binary stream (max-likelihood value), diff --git a/octomap/include/octomap/OccupancyOcTreeBase.hxx b/octomap/include/octomap/OccupancyOcTreeBase.hxx index 8da13203..badd60ee 100644 --- a/octomap/include/octomap/OccupancyOcTreeBase.hxx +++ b/octomap/include/octomap/OccupancyOcTreeBase.hxx @@ -384,7 +384,7 @@ namespace octomap { } else { // not a pruned node, create requested child - node->createChild(pos); + this->createNodeChild(node, pos); this->tree_size++; this->size_changed = true; created_node = true; @@ -392,9 +392,9 @@ namespace octomap { } if (lazy_eval) - return updateNodeRecurs(node->getChild(pos), created_node, key, depth+1, log_odds_update, lazy_eval); + return updateNodeRecurs(this->getNodeChild(node, pos), created_node, key, depth+1, log_odds_update, lazy_eval); else { - NODE* retval = updateNodeRecurs(node->getChild(pos), created_node, key, depth+1, log_odds_update, lazy_eval); + NODE* retval = updateNodeRecurs(this->getNodeChild(node, pos), created_node, key, depth+1, log_odds_update, lazy_eval); // prune node if possible, otherwise set own probability // note: combining both did not lead to a speedup! if (this->pruneNode(node)){ @@ -453,7 +453,7 @@ namespace octomap { } else { // not a pruned node, create requested child - node->createChild(pos); + this->createNodeChild(node, pos); this->tree_size++; this->size_changed = true; created_node = true; @@ -461,9 +461,9 @@ namespace octomap { } if (lazy_eval) - return setNodeValueRecurs(node->getChild(pos), created_node, key, depth+1, log_odds_value, lazy_eval); + return setNodeValueRecurs(this->getNodeChild(node, pos), created_node, key, depth+1, log_odds_value, lazy_eval); else { - NODE* retval = setNodeValueRecurs(node->getChild(pos), created_node, key, depth+1, log_odds_value, lazy_eval); + NODE* retval = setNodeValueRecurs(this->getNodeChild(node, pos), created_node, key, depth+1, log_odds_value, lazy_eval); // prune node if possible, otherwise set own probability // note: combining both did not lead to a speedup! if (this->pruneNode(node)){ @@ -516,7 +516,7 @@ namespace octomap { if (depth < this->tree_depth){ for (unsigned int i=0; i<8; i++) { if (node->childExists(i)) { - updateInnerOccupancyRecurs(node->getChild(i), depth+1); + updateInnerOccupancyRecurs(this->getNodeChild(node, i), depth+1); } } } @@ -547,7 +547,7 @@ namespace octomap { if (depth < max_depth) { for (unsigned int i=0; i<8; i++) { if (node->childExists(i)) { - toMaxLikelihoodRecurs(node->getChild(i), depth+1, max_depth); + toMaxLikelihoodRecurs(this->getNodeChild(node, i), depth+1, max_depth); } } } @@ -961,7 +961,7 @@ namespace octomap { } template - std::istream& OccupancyOcTreeBase::readBinaryNode(std::istream &s, NODE* node) const { + std::istream& OccupancyOcTreeBase::readBinaryNode(std::istream &s, NODE* node){ assert(node); @@ -984,35 +984,35 @@ namespace octomap { for (unsigned int i=0; i<4; i++) { if ((child1to4[i*2] == 1) && (child1to4[i*2+1] == 0)) { // child is free leaf - node->createChild(i); - node->getChild(i)->setLogOdds(this->clamping_thres_min); + this->createNodeChild(node, i); + this->getNodeChild(node, i)->setLogOdds(this->clamping_thres_min); } else if ((child1to4[i*2] == 0) && (child1to4[i*2+1] == 1)) { // child is occupied leaf - node->createChild(i); - node->getChild(i)->setLogOdds(this->clamping_thres_max); + this->createNodeChild(node, i); + this->getNodeChild(node, i)->setLogOdds(this->clamping_thres_max); } else if ((child1to4[i*2] == 1) && (child1to4[i*2+1] == 1)) { // child has children - node->createChild(i); - node->getChild(i)->setLogOdds(-200.); // child is unkown, we leave it uninitialized + this->createNodeChild(node, i); + this->getNodeChild(node, i)->setLogOdds(-200.); // child is unkown, we leave it uninitialized } } for (unsigned int i=0; i<4; i++) { if ((child5to8[i*2] == 1) && (child5to8[i*2+1] == 0)) { // child is free leaf - node->createChild(i+4); - node->getChild(i+4)->setLogOdds(this->clamping_thres_min); + this->createNodeChild(node, i+4); + this->getNodeChild(node, i+4)->setLogOdds(this->clamping_thres_min); } else if ((child5to8[i*2] == 0) && (child5to8[i*2+1] == 1)) { // child is occupied leaf - node->createChild(i+4); - node->getChild(i+4)->setLogOdds(this->clamping_thres_max); + this->createNodeChild(node, i+4); + this->getNodeChild(node, i+4)->setLogOdds(this->clamping_thres_max); } else if ((child5to8[i*2] == 1) && (child5to8[i*2+1] == 1)) { // child has children - node->createChild(i+4); - node->getChild(i+4)->setLogOdds(-200.); // set occupancy when all children have been read + this->createNodeChild(node, i+4); + this->getNodeChild(node, i+4)->setLogOdds(-200.); // set occupancy when all children have been read } // child is unkown, we leave it uninitialized } @@ -1020,7 +1020,7 @@ namespace octomap { // read children's children and set the label for (unsigned int i=0; i<8; i++) { if (node->childExists(i)) { - NODE* child = node->getChild(i); + NODE* child = this->getNodeChild(node, i); if (fabs(child->getLogOdds() + 200.)<1e-3) { readBinaryNode(s, child); child->setLogOdds(child->getMaxChildLogOdds()); @@ -1051,7 +1051,7 @@ namespace octomap { for (unsigned int i=0; i<4; i++) { if (node->childExists(i)) { - const NODE* child = node->getChild(i); + const NODE* child = this->getNodeChild(node, i); if (child->hasChildren()) { child1to4[i*2] = 1; child1to4[i*2+1] = 1; } else if (this->isNodeOccupied(child)) { child1to4[i*2] = 0; child1to4[i*2+1] = 1; } else { child1to4[i*2] = 1; child1to4[i*2+1] = 0; } @@ -1063,7 +1063,7 @@ namespace octomap { for (unsigned int i=0; i<4; i++) { if (node->childExists(i+4)) { - const NODE* child = node->getChild(i+4); + const NODE* child = this->getNodeChild(node, i+4); if (child->hasChildren()) { child5to8[i*2] = 1; child5to8[i*2+1] = 1; } else if (this->isNodeOccupied(child)) { child5to8[i*2] = 0; child5to8[i*2+1] = 1; } else { child5to8[i*2] = 1; child5to8[i*2+1] = 0; } @@ -1085,7 +1085,7 @@ namespace octomap { // write children's children for (unsigned int i=0; i<8; i++) { if (node->childExists(i)) { - const NODE* child = node->getChild(i); + const NODE* child = this->getNodeChild(node, i); if (child->hasChildren()) { writeBinaryNode(s, child); } diff --git a/octomap/src/ColorOcTree.cpp b/octomap/src/ColorOcTree.cpp index b8857fa0..13e5bac2 100644 --- a/octomap/src/ColorOcTree.cpp +++ b/octomap/src/ColorOcTree.cpp @@ -55,10 +55,12 @@ namespace octomap { int mr(0), mg(0), mb(0); int c(0); for (int i=0; i<8; i++) { - if (childExists(i) && getChild(i)->isColorSet()) { - mr += getChild(i)->getColor().r; - mg += getChild(i)->getColor().g; - mb += getChild(i)->getColor().b; + ColorOcTreeNode* child = static_cast(children[i]); + + if (childExists(i) && child->isColorSet()) { + mr += child->getColor().r; + mg += child->getColor().g; + mb += child->getColor().b; ++c; } } @@ -82,7 +84,12 @@ namespace octomap { bool ColorOcTreeNode::pruneNode() { // checks for equal occupancy only, color ignored + // TODO FIXME move to tree! + return false; + /** if (!this->collapsible()) return false; + + // set occupancy value setLogOdds(getChild(0)->getLogOdds()); // set color to average color @@ -94,6 +101,7 @@ namespace octomap { delete[] children; children = NULL; return true; + **/ } void ColorOcTreeNode::expandNode() { @@ -171,7 +179,7 @@ namespace octomap { if (depth < this->tree_depth){ for (unsigned int i=0; i<8; i++) { if (node->childExists(i)) { - updateInnerOccupancyRecurs(node->getChild(i), depth+1); + updateInnerOccupancyRecurs(getNodeChild(node, i), depth+1); } } } diff --git a/octomap/src/CountingOcTree.cpp b/octomap/src/CountingOcTree.cpp index 7b147625..b0130360 100644 --- a/octomap/src/CountingOcTree.cpp +++ b/octomap/src/CountingOcTree.cpp @@ -48,6 +48,7 @@ namespace octomap { } + // TODO: move to tree void CountingOcTreeNode::expandNode(){ assert(!hasChildren()); @@ -59,16 +60,6 @@ namespace octomap { } } - bool CountingOcTreeNode::createChild(unsigned int i) { - if (children == NULL) { - allocChildren(); - } - assert (children[i] == NULL); - children[i] = new CountingOcTreeNode(); - return true; - } - - /// implementation of CountingOcTree -------------------------------------- diff --git a/octomap/src/OcTreeNode.cpp b/octomap/src/OcTreeNode.cpp index a6e43193..47d51bc5 100644 --- a/octomap/src/OcTreeNode.cpp +++ b/octomap/src/OcTreeNode.cpp @@ -49,17 +49,7 @@ namespace octomap { OcTreeNode::~OcTreeNode(){ } - // TODO: Use Curiously Recurring Template Pattern instead of copying full function - // (same for getChild) - bool OcTreeNode::createChild(unsigned int i) { - if (children == NULL) { - allocChildren(); - } - assert (children[i] == NULL); - children[i] = new OcTreeNode(); - return true; - } - + // ============================================================ // = occupancy probability ================================== // ============================================================ @@ -69,10 +59,11 @@ namespace octomap { char c = 0; for (unsigned int i=0; i<8; i++) { if (childExists(i)) { - mean += getChild(i)->getOccupancy(); + mean += static_cast(children[i])->getOccupancy(); // TODO check if works generally c++; } } + if (c) mean /= (double) c; @@ -83,7 +74,7 @@ namespace octomap { float max = -std::numeric_limits::max(); for (unsigned int i=0; i<8; i++) { if (childExists(i)) { - float l = getChild(i)->getLogOdds(); + float l = static_cast(children[i])->getLogOdds(); // TODO check if works generally if (l > max) max = l; } diff --git a/octomap/src/testing/test_iterators.cpp b/octomap/src/testing/test_iterators.cpp index a2b77c19..0a0798ad 100644 --- a/octomap/src/testing/test_iterators.cpp +++ b/octomap/src/testing/test_iterators.cpp @@ -51,9 +51,9 @@ void getLeafNodesRecurs(std::list& voxels, if (node->childExists(i)) { computeChildCenter(i, center_offset, parent_center, search_center); - getLeafNodesRecurs(voxels, max_depth, node->getChild(i), depth+1, search_center, tree_center, tree, occupied); + getLeafNodesRecurs(voxels, max_depth, tree->getNodeChild(node, i), depth+1, search_center, tree_center, tree, occupied); - } // GetChild + } } } else { @@ -72,7 +72,7 @@ void getVoxelsRecurs(std::list& voxels, unsigned int max_depth, OcTreeNode* node, unsigned int depth, const point3d& parent_center, const point3d& tree_center, - double resolution){ + OcTree* tree){ if ((depth <= max_depth) && (node != NULL) ) { if (node->hasChildren() && (depth != max_depth)) { @@ -83,12 +83,12 @@ void getVoxelsRecurs(std::list& voxels, for (unsigned int i = 0; i < 8; i++) { if (node->childExists(i)) { computeChildCenter(i, (float) center_offset, parent_center, search_center); - getVoxelsRecurs(voxels, max_depth, node->getChild(i), depth + 1, search_center, tree_center, resolution); + getVoxelsRecurs(voxels, max_depth, tree->getNodeChild(node, i), depth + 1, search_center, tree_center, tree); } } // depth } - double voxelSize = resolution * pow(2., double(16 - depth)); + double voxelSize = tree->getResolution() * pow(2., double(16 - depth)); voxels.push_back(std::make_pair(parent_center - tree_center, voxelSize)); } } @@ -353,7 +353,7 @@ int main(int argc, char** argv) { list_depr.clear(); gettimeofday(&start, NULL); // start timer - getVoxelsRecurs(list_depr,maxDepth,tree->getRoot(), 0, tree_center, tree_center, tree->getResolution()); + getVoxelsRecurs(list_depr,maxDepth,tree->getRoot(), 0, tree_center, tree_center, tree); gettimeofday(&stop, NULL); // stop timer time_depr = timediff(start, stop); From 3bd6ebac5c86218d99db3d47e9c417101c63cbc1 Mon Sep 17 00:00:00 2001 From: Armin Hornung Date: Fri, 8 Jan 2016 21:30:51 +0100 Subject: [PATCH 06/28] Adding copyData() fct to nodes for expansion / pruning, cleaning up old fcts from ColorOcTreeNode (mostly uncovered by unit tests - untested!) --- octomap/include/octomap/ColorOcTree.h | 28 ++++-------- octomap/include/octomap/OcTreeBaseImpl.hxx | 6 +-- octomap/include/octomap/OcTreeDataNode.h | 11 ++++- octomap/include/octomap/OcTreeDataNode.hxx | 8 +++- octomap/include/octomap/OcTreeStamped.h | 7 ++- octomap/src/ColorOcTree.cpp | 53 +++++++++------------- 6 files changed, 56 insertions(+), 57 deletions(-) diff --git a/octomap/include/octomap/ColorOcTree.h b/octomap/include/octomap/ColorOcTree.h index 1372a8d1..3d24199a 100644 --- a/octomap/include/octomap/ColorOcTree.h +++ b/octomap/include/octomap/ColorOcTree.h @@ -41,9 +41,13 @@ namespace octomap { + // forward declaraton for "friend" + class ColorOcTree; + // node definition class ColorOcTreeNode : public OcTreeNode { public: + friend class ColorOcTree; // needs access to node children (inherited) class Color { public: @@ -68,25 +72,11 @@ namespace octomap { return (rhs.value == value && rhs.color == color); } - // children - //TODO remove - inline ColorOcTreeNode* getChild(unsigned int i) { - return static_cast (children[i]); - } - inline const ColorOcTreeNode* getChild(unsigned int i) const { - return static_cast (children[i]); - } - - bool createChild(unsigned int i) { - if (children == NULL) allocChildren(); - children[i] = new ColorOcTreeNode(); - return true; + void copyData(const ColorOcTreeNode& from){ + OcTreeNode::copyData(from); + this->color = from.getColor(); } - - // TODO: move into tree! - bool pruneNode(); - void expandNode(); - + inline Color getColor() const { return color; } inline void setColor(Color c) {this->color = c; } inline void setColor(unsigned char r, unsigned char g, unsigned char b) { @@ -126,6 +116,8 @@ namespace octomap { ColorOcTree* create() const {return new ColorOcTree(resolution); } std::string getTreeType() const {return "ColorOcTree";} + + bool pruneNode(ColorOcTreeNode* node); // set node color at given key or coordinate. Replaces previous color. ColorOcTreeNode* setNodeColor(const OcTreeKey& key, const unsigned char& r, diff --git a/octomap/include/octomap/OcTreeBaseImpl.hxx b/octomap/include/octomap/OcTreeBaseImpl.hxx index d920fab3..f6a83701 100644 --- a/octomap/include/octomap/OcTreeBaseImpl.hxx +++ b/octomap/include/octomap/OcTreeBaseImpl.hxx @@ -178,7 +178,7 @@ namespace octomap { if (node->children == NULL) { allocNodeChildren(node); } - assert (node.children[childIdx] == NULL); + assert (node->children[childIdx] == NULL); NODE* newNode = new NODE(); node->children[childIdx] = static_cast(newNode); return newNode; @@ -233,7 +233,7 @@ namespace octomap { for (unsigned int k=0; k<8; k++) { NODE* newNode = createNodeChild(node, k); - newNode->setValue(node->getValue()); // TODO: copy ctor for data nodes instead? + newNode->copyData(*node); } } @@ -244,7 +244,7 @@ namespace octomap { return false; // set value to children's values (all assumed equal) - node->setValue(getNodeChild(node, 0)->getValue()); + node->copyData(*(getNodeChild(node, 0))); // delete children for (unsigned int i=0;i<8;i++) { diff --git a/octomap/include/octomap/OcTreeDataNode.h b/octomap/include/octomap/OcTreeDataNode.h index 7cce9e7d..9785e5d1 100644 --- a/octomap/include/octomap/OcTreeDataNode.h +++ b/octomap/include/octomap/OcTreeDataNode.h @@ -68,13 +68,22 @@ namespace octomap { OcTreeDataNode(); OcTreeDataNode(T initVal); - /// Copy constructor, performs a recursive deep-copy of all children + + /// Copy constructor, performs a recursive deep-copy of all children + /// including node data in "value" OcTreeDataNode(const OcTreeDataNode& rhs); ~OcTreeDataNode(); + /// Copy the payload (data in "value") from rhs into this node + /// Opposed to copy ctor, this does not clone the children as well + void copyData(const OcTreeDataNode& from); + /// Equals operator, compares if the stored value is identical bool operator==(const OcTreeDataNode& rhs) const; + + + // -- children ---------------------------------- diff --git a/octomap/include/octomap/OcTreeDataNode.hxx b/octomap/include/octomap/OcTreeDataNode.hxx index 51e37374..3364f979 100644 --- a/octomap/include/octomap/OcTreeDataNode.hxx +++ b/octomap/include/octomap/OcTreeDataNode.hxx @@ -60,8 +60,7 @@ namespace octomap { } } } - - + template OcTreeDataNode::~OcTreeDataNode() { @@ -75,6 +74,11 @@ namespace octomap { } } + + template + void OcTreeDataNode::copyData(const OcTreeDataNode& from){ + value = from.value; + } template bool OcTreeDataNode::operator== (const OcTreeDataNode& rhs) const{ diff --git a/octomap/include/octomap/OcTreeStamped.h b/octomap/include/octomap/OcTreeStamped.h index 86e925ae..b56d7863 100644 --- a/octomap/include/octomap/OcTreeStamped.h +++ b/octomap/include/octomap/OcTreeStamped.h @@ -51,7 +51,12 @@ namespace octomap { bool operator==(const OcTreeNodeStamped& rhs) const{ return (rhs.value == value && rhs.timestamp == timestamp); - } + } + + void copyData(const OcTreeNodeStamped& from){ + OcTreeNode::copyData(from); + timestamp = from.getTimestamp(); + } // timestamp inline unsigned int getTimestamp() const { return timestamp; } diff --git a/octomap/src/ColorOcTree.cpp b/octomap/src/ColorOcTree.cpp index 13e5bac2..6cbf6341 100644 --- a/octomap/src/ColorOcTree.cpp +++ b/octomap/src/ColorOcTree.cpp @@ -80,38 +80,6 @@ namespace octomap { color = getAverageChildColor(); } - // pruning ============= - - bool ColorOcTreeNode::pruneNode() { - // checks for equal occupancy only, color ignored - // TODO FIXME move to tree! - return false; - /** - if (!this->collapsible()) return false; - - - // set occupancy value - setLogOdds(getChild(0)->getLogOdds()); - // set color to average color - if (isColorSet()) color = getAverageChildColor(); - // delete children - for (unsigned int i=0;i<8;i++) { - delete static_cast(children[i]); - } - delete[] children; - children = NULL; - return true; - **/ - } - - void ColorOcTreeNode::expandNode() { - assert(!hasChildren()); - for (unsigned int k=0; k<8; k++) { - createChild(k); - getChild(k)->setValue(value); - getChild(k)->setColor(color); - } - } // tree implementation -------------------------------------- @@ -125,6 +93,27 @@ namespace octomap { } return n; } + + bool ColorOcTree::pruneNode(ColorOcTreeNode* node) { + assert(0); + if (!isNodeCollapsible(node)) // TODO: overload here, check occupancy only? + return false; + + // set value to children's values (all assumed equal) + node->copyData(*(getNodeChild(node, 0))); + + if (node->isColorSet()) // TODO check + node->setColor(node->getAverageChildColor()); + + // delete children + for (unsigned int i=0;i<8;i++) { + delete static_cast(node->children[i]); + } + delete[] node->children; + node->children = NULL; + + return true; + } ColorOcTreeNode* ColorOcTree::averageNodeColor(const OcTreeKey& key, const unsigned char& r, From 95a549902d91bb85ac8f093bd7bd2b6ab0b0cc9f Mon Sep 17 00:00:00 2001 From: Armin Hornung Date: Sun, 10 Jan 2016 13:59:08 +0100 Subject: [PATCH 07/28] Fixing memleaks in test_io.cpp (missing deletes) --- octomap/src/testing/test_io.cpp | 224 +++++++++++++++++--------------- 1 file changed, 119 insertions(+), 105 deletions(-) diff --git a/octomap/src/testing/test_io.cpp b/octomap/src/testing/test_io.cpp index 031ff9e3..88ac9831 100644 --- a/octomap/src/testing/test_io.cpp +++ b/octomap/src/testing/test_io.cpp @@ -19,119 +19,133 @@ int main(int argc, char** argv) { std::cout << "Testing empty OcTree...\n"; //empty tree - OcTree emptyTree(0.999); - EXPECT_EQ(emptyTree.size(), 0); - EXPECT_TRUE(emptyTree.writeBinary("empty.bt")); - EXPECT_TRUE(emptyTree.write("empty.ot")); - - OcTree emptyReadTree(0.2); - EXPECT_TRUE(emptyReadTree.readBinary("empty.bt")); - EXPECT_EQ(emptyReadTree.size(), 0); - EXPECT_TRUE(emptyTree == emptyReadTree); - - EXPECT_TRUE(emptyReadTree.read("empty.ot")); - EXPECT_EQ(emptyReadTree.size(), 0); - EXPECT_TRUE(emptyTree == emptyReadTree); + { + OcTree emptyTree(0.999); + EXPECT_EQ(emptyTree.size(), 0); + EXPECT_TRUE(emptyTree.writeBinary("empty.bt")); + EXPECT_TRUE(emptyTree.write("empty.ot")); + + OcTree emptyReadTree(0.2); + EXPECT_TRUE(emptyReadTree.readBinary("empty.bt")); + EXPECT_EQ(emptyReadTree.size(), 0); + EXPECT_TRUE(emptyTree == emptyReadTree); + + + AbstractOcTree* readTreeAbstract = AbstractOcTree::read("empty.ot"); + EXPECT_TRUE(readTreeAbstract); + OcTree* readTreeOt = dynamic_cast(readTreeAbstract); + EXPECT_TRUE(readTreeOt); + EXPECT_EQ(readTreeOt->size(), 0); + EXPECT_TRUE(emptyTree == *readTreeOt); + delete readTreeOt; + } std::cout << "Testing reference OcTree from file ...\n"; string filename = string(argv[1]); - string filenameOt = "test_io_file.ot"; - string filenameBtOut = "test_io_file.bt"; - string filenameBtCopyOut = "test_io_file_copy.bt"; - - // read reference tree from input file - OcTree tree (0.1); - EXPECT_TRUE (tree.readBinary(filename)); - - std::cout << " Copy Constructor / assignment / ==\n"; - // test copy constructor / assignment: - OcTree* treeCopy = new OcTree(tree); - EXPECT_TRUE(tree == *treeCopy); - EXPECT_TRUE(treeCopy->writeBinary(filenameBtCopyOut)); - - // change a tree property, trees must be different afterwards - treeCopy->setResolution(tree.getResolution()*2.0); - EXPECT_FALSE(tree == *treeCopy); - treeCopy->setResolution(tree.getResolution()); - EXPECT_TRUE(tree == *treeCopy); - - // flip one value, trees must be different afterwards: - point3d pt(0.5, 0.5, 0.5); - OcTreeNode* node = treeCopy->search(pt); - if (node && treeCopy->isNodeOccupied(node)) - treeCopy->updateNode(pt, false); - else - treeCopy->updateNode(pt, true); - - EXPECT_FALSE(tree == *treeCopy); - - - delete treeCopy; - - std::cout << " Swap\n"; - // test swap: - OcTree emptyT(tree.getResolution()); - OcTree emptySw(emptyT); - OcTree otherSw(tree); - emptySw.swapContent(otherSw); - EXPECT_FALSE(emptyT == emptySw); - EXPECT_TRUE(emptySw == tree); - EXPECT_TRUE(otherSw == emptyT); - - - // write again to bt, read & compare - EXPECT_TRUE(tree.writeBinary(filenameBtOut)); - OcTree readTreeBt(0.1); - EXPECT_TRUE(readTreeBt.readBinary(filenameBtOut)); - EXPECT_TRUE(tree == readTreeBt); - - std::cout <<" Write to .ot / read through AbstractOcTree\n"; - // now write to .ot, read & compare - EXPECT_TRUE(tree.write(filenameOt)); - - AbstractOcTree* readTreeAbstract = AbstractOcTree::read(filenameOt); - EXPECT_TRUE(readTreeAbstract); - - OcTree* readTreeOt = dynamic_cast(readTreeAbstract); - EXPECT_TRUE(readTreeOt); - EXPECT_TRUE(tree == *readTreeOt); - - // sanity test for "==": flip one node, compare again - point3d coord(0.1f, 0.1f, 0.1f); - node = readTreeOt->search(coord); - if (node && readTreeOt->isNodeOccupied(node)) - readTreeOt->updateNode(coord, false); - else - readTreeOt->updateNode(coord, true); - - EXPECT_FALSE(tree == *readTreeOt); + { + string filenameOt = "test_io_file.ot"; + string filenameBtOut = "test_io_file.bt"; + string filenameBtCopyOut = "test_io_file_copy.bt"; + + // read reference tree from input file + OcTree tree (0.1); + EXPECT_TRUE (tree.readBinary(filename)); + + std::cout << " Copy Constructor / assignment / ==\n"; + // test copy constructor / assignment: + OcTree* treeCopy = new OcTree(tree); + EXPECT_TRUE(tree == *treeCopy); + EXPECT_TRUE(treeCopy->writeBinary(filenameBtCopyOut)); + + // change a tree property, trees must be different afterwards + treeCopy->setResolution(tree.getResolution()*2.0); + EXPECT_FALSE(tree == *treeCopy); + treeCopy->setResolution(tree.getResolution()); + EXPECT_TRUE(tree == *treeCopy); + + // flip one value, trees must be different afterwards: + point3d pt(0.5, 0.5, 0.5); + OcTreeNode* node = treeCopy->search(pt); + if (node && treeCopy->isNodeOccupied(node)) + treeCopy->updateNode(pt, false); + else + treeCopy->updateNode(pt, true); + + EXPECT_FALSE(tree == *treeCopy); + + + delete treeCopy; + + std::cout << " Swap\n"; + // test swap: + OcTree emptyT(tree.getResolution()); + OcTree emptySw(emptyT); + OcTree otherSw(tree); + emptySw.swapContent(otherSw); + EXPECT_FALSE(emptyT == emptySw); + EXPECT_TRUE(emptySw == tree); + EXPECT_TRUE(otherSw == emptyT); + + + // write again to bt, read & compare + EXPECT_TRUE(tree.writeBinary(filenameBtOut)); + OcTree readTreeBt(0.1); + EXPECT_TRUE(readTreeBt.readBinary(filenameBtOut)); + EXPECT_TRUE(tree == readTreeBt); + + std::cout <<" Write to .ot / read through AbstractOcTree\n"; + // now write to .ot, read & compare + EXPECT_TRUE(tree.write(filenameOt)); + + AbstractOcTree* readTreeAbstract = AbstractOcTree::read(filenameOt); + EXPECT_TRUE(readTreeAbstract); + + OcTree* readTreeOt = dynamic_cast(readTreeAbstract); + EXPECT_TRUE(readTreeOt); + EXPECT_TRUE(tree == *readTreeOt); + + // sanity test for "==": flip one node, compare again + point3d coord(0.1f, 0.1f, 0.1f); + node = readTreeOt->search(coord); + if (node && readTreeOt->isNodeOccupied(node)) + readTreeOt->updateNode(coord, false); + else + readTreeOt->updateNode(coord, true); + + EXPECT_FALSE(tree == *readTreeOt); + + delete readTreeOt; + } // simple test for tree headers (color) - std::cout << "Testing ColorOcTree...\n"; - double res = 0.02; - std::string filenameColor = "test_io_color_file.ot"; - ColorOcTree colorTree(res); - EXPECT_EQ(colorTree.getTreeType(), "ColorOcTree"); - ColorOcTreeNode* colorNode = colorTree.updateNode(point3d(0.0, 0.0, 0.0), true); - ColorOcTreeNode::Color color_red(255, 0, 0); - colorNode->setColor(color_red); - colorTree.setNodeColor(0.0, 0.0, 0.0, 255, 0, 0); - colorTree.updateNode(point3d(0.1f, 0.1f, 0.1f), true); - colorTree.setNodeColor(0.1f, 0.1f, 0.1f, 0, 0, 255); - - EXPECT_TRUE(colorTree.write(filenameColor)); - readTreeAbstract = AbstractOcTree::read(filenameColor); - EXPECT_TRUE(readTreeAbstract); - EXPECT_EQ(colorTree.getTreeType(), readTreeAbstract->getTreeType()); - ColorOcTree* readColorTree = dynamic_cast(readTreeAbstract); - EXPECT_TRUE(readColorTree); - EXPECT_TRUE(colorTree == *readColorTree); - colorNode = colorTree.search(0.0, 0.0, 0.0); - EXPECT_TRUE(colorNode); - EXPECT_EQ(colorNode->getColor(), color_red); + { + std::cout << "Testing ColorOcTree...\n"; + double res = 0.02; + std::string filenameColor = "test_io_color_file.ot"; + ColorOcTree colorTree(res); + EXPECT_EQ(colorTree.getTreeType(), "ColorOcTree"); + ColorOcTreeNode* colorNode = colorTree.updateNode(point3d(0.0, 0.0, 0.0), true); + ColorOcTreeNode::Color color_red(255, 0, 0); + colorNode->setColor(color_red); + colorTree.setNodeColor(0.0, 0.0, 0.0, 255, 0, 0); + colorTree.updateNode(point3d(0.1f, 0.1f, 0.1f), true); + colorTree.setNodeColor(0.1f, 0.1f, 0.1f, 0, 0, 255); + + EXPECT_TRUE(colorTree.write(filenameColor)); + AbstractOcTree* readTreeAbstract = AbstractOcTree::read(filenameColor); + EXPECT_TRUE(readTreeAbstract); + EXPECT_EQ(colorTree.getTreeType(), readTreeAbstract->getTreeType()); + ColorOcTree* readColorTree = dynamic_cast(readTreeAbstract); + EXPECT_TRUE(readColorTree); + EXPECT_TRUE(colorTree == *readColorTree); + colorNode = colorTree.search(0.0, 0.0, 0.0); + EXPECT_TRUE(colorNode); + EXPECT_EQ(colorNode->getColor(), color_red); + delete readColorTree; + } From 6197d0d00cc458bab369c6d653e9bd6ad3112021 Mon Sep 17 00:00:00 2001 From: Armin Hornung Date: Sun, 10 Jan 2016 21:29:27 +0100 Subject: [PATCH 08/28] Fixing memory deallocation by moving it into OcTreeBaseImpl, which now has the responsibility of maintaining the tree structure (= "children" member of nodes) --- octomap/include/octomap/OcTreeBaseImpl.h | 3 ++ octomap/include/octomap/OcTreeBaseImpl.hxx | 38 +++++++++++++++------- octomap/include/octomap/OcTreeDataNode.h | 3 ++ octomap/include/octomap/OcTreeDataNode.hxx | 12 ++----- octomap/valgrind_memcheck.supp | 7 ++++ 5 files changed, 43 insertions(+), 20 deletions(-) diff --git a/octomap/include/octomap/OcTreeBaseImpl.h b/octomap/include/octomap/OcTreeBaseImpl.h index 95204b6e..6c852492 100644 --- a/octomap/include/octomap/OcTreeBaseImpl.h +++ b/octomap/include/octomap/OcTreeBaseImpl.h @@ -491,6 +491,9 @@ namespace octomap { /// recursive call of writeData() std::ostream& writeNodesRecurs(const NODE*, std::ostream &s) const; + + /// recursive delete of node and all children (deallocates memory) + void deleteNodeRecurs(NODE* node); /// recursive call of deleteNode() bool deleteNodeRecurs(NODE* node, unsigned int depth, unsigned int max_depth, const OcTreeKey& key); diff --git a/octomap/include/octomap/OcTreeBaseImpl.hxx b/octomap/include/octomap/OcTreeBaseImpl.hxx index f6a83701..da4d42b9 100644 --- a/octomap/include/octomap/OcTreeBaseImpl.hxx +++ b/octomap/include/octomap/OcTreeBaseImpl.hxx @@ -66,10 +66,9 @@ namespace octomap { template OcTreeBaseImpl::~OcTreeBaseImpl(){ - if (root) - delete root; - - root = NULL; + if (root){ + deleteNodeRecurs(root); + } } @@ -188,7 +187,7 @@ namespace octomap { void OcTreeBaseImpl::deleteNodeChild(NODE* node, unsigned int childIdx){ assert((childIdx < 8) && (node->children != NULL)); assert(node->children[childIdx] != NULL); - delete static_cast(node->children[childIdx]); + delete static_cast(node->children[childIdx]); // TODO delete check if empty node->children[childIdx] = NULL; } @@ -246,9 +245,9 @@ namespace octomap { // set value to children's values (all assumed equal) node->copyData(*(getNodeChild(node, 0))); - // delete children + // delete children (known to be leafs at this point!) for (unsigned int i=0;i<8;i++) { - delete static_cast(node->children[i]); + deleteNodeChild(node, i); } delete[] node->children; node->children = NULL; @@ -481,15 +480,13 @@ namespace octomap { template void OcTreeBaseImpl::clear() { if (this->root){ - delete this->root; - this->root = NULL; + deleteNodeRecurs(root); this->tree_size = 0; // max extent of tree changed: this->size_changed = true; } } - template void OcTreeBaseImpl::prune() { if (root == NULL) @@ -628,6 +625,25 @@ namespace octomap { } return true; } + + template + void OcTreeBaseImpl::deleteNodeRecurs(NODE* node){ + assert(node); + // TODO: maintain tree size? + + if (node->children != NULL) { + for (unsigned int i=0; i<8; i++) { + if (node->children[i] != NULL) + this->deleteNodeRecurs(static_cast(node->children[i])); + } + delete[] node->children; + node->children = NULL; + } // else: node has no children + + delete node; + node = NULL; + } + template bool OcTreeBaseImpl::deleteNodeRecurs(NODE* node, unsigned int depth, unsigned int max_depth, const OcTreeKey& key){ @@ -655,6 +671,7 @@ namespace octomap { bool deleteChild = deleteNodeRecurs(getNodeChild(node, pos), depth+1, max_depth, key); if (deleteChild){ // TODO: lazy eval? + // TODO delete check depth, what happens to inner nodes with children? this->deleteNodeChild(node, pos); this->tree_size-=1; this->size_changed = true; @@ -666,7 +683,6 @@ namespace octomap { } // node did not lose a child, or still has other children return false; - } template diff --git a/octomap/include/octomap/OcTreeDataNode.h b/octomap/include/octomap/OcTreeDataNode.h index 9785e5d1..ca9cc8b3 100644 --- a/octomap/include/octomap/OcTreeDataNode.h +++ b/octomap/include/octomap/OcTreeDataNode.h @@ -73,6 +73,8 @@ namespace octomap { /// including node data in "value" OcTreeDataNode(const OcTreeDataNode& rhs); + /// Delete only own members. + /// OcTree maintains tree structure and must have deleted children already ~OcTreeDataNode(); /// Copy the payload (data in "value") from rhs into this node @@ -118,6 +120,7 @@ namespace octomap { void allocChildren(); /// pointer to array of children, may be NULL + /// @note The tree class manages this pointer, the array, and the memory for it! void** children; /// stored data (payload) T value; diff --git a/octomap/include/octomap/OcTreeDataNode.hxx b/octomap/include/octomap/OcTreeDataNode.hxx index 3364f979..81fedb59 100644 --- a/octomap/include/octomap/OcTreeDataNode.hxx +++ b/octomap/include/octomap/OcTreeDataNode.hxx @@ -64,15 +64,9 @@ namespace octomap { template OcTreeDataNode::~OcTreeDataNode() { - if (children != NULL) { - for (unsigned int i=0; i<8; i++) { - if (children[i] != NULL) - delete static_cast*>(children[i]); - } - // TODO: ensure correct destructor is called for each derived node! - delete[] children; - } - + // Delete only own members. OcTree maintains tree structure and must have deleted + // children already + assert(!hasChildren()); } template diff --git a/octomap/valgrind_memcheck.supp b/octomap/valgrind_memcheck.supp index 69593d0b..8c8d0378 100644 --- a/octomap/valgrind_memcheck.supp +++ b/octomap/valgrind_memcheck.supp @@ -1,3 +1,10 @@ +# Suppression file for valgrind memcheck on OctoMap. +# Suppresses the "leaks" by the static member initializer which cannot be avoided. +# +# You can run valgrind on an OctoMap binary (e.g. a unit test) with: +# valgrind --tool=memcheck --leak-check=full --suppressions=valgrind_memcheck.supp bin/test_.... +# + { static_member_init_std_string Memcheck:Leak From 175754aae5eae4423ef7d4496151980c67e0cc25 Mon Sep 17 00:00:00 2001 From: Armin Hornung Date: Tue, 12 Jan 2016 22:23:09 +0100 Subject: [PATCH 09/28] Changing void* to AbstractOcTreeNode* --- octomap/include/octomap/OcTreeBaseImpl.h | 3 +++ octomap/include/octomap/OcTreeBaseImpl.hxx | 2 +- octomap/include/octomap/OcTreeDataNode.h | 3 ++- octomap/include/octomap/OcTreeDataNode.hxx | 2 +- octomap/valgrind_memcheck.supp | 2 +- 5 files changed, 8 insertions(+), 4 deletions(-) diff --git a/octomap/include/octomap/OcTreeBaseImpl.h b/octomap/include/octomap/OcTreeBaseImpl.h index 6c852492..d56a35a5 100644 --- a/octomap/include/octomap/OcTreeBaseImpl.h +++ b/octomap/include/octomap/OcTreeBaseImpl.h @@ -47,6 +47,9 @@ namespace octomap { + + // forward declaration for NODE children array + class AbstractOcTreeNode; /** diff --git a/octomap/include/octomap/OcTreeBaseImpl.hxx b/octomap/include/octomap/OcTreeBaseImpl.hxx index da4d42b9..84bd6072 100644 --- a/octomap/include/octomap/OcTreeBaseImpl.hxx +++ b/octomap/include/octomap/OcTreeBaseImpl.hxx @@ -179,7 +179,7 @@ namespace octomap { } assert (node->children[childIdx] == NULL); NODE* newNode = new NODE(); - node->children[childIdx] = static_cast(newNode); + node->children[childIdx] = static_cast(newNode); return newNode; } diff --git a/octomap/include/octomap/OcTreeDataNode.h b/octomap/include/octomap/OcTreeDataNode.h index ca9cc8b3..3d74d6b7 100644 --- a/octomap/include/octomap/OcTreeDataNode.h +++ b/octomap/include/octomap/OcTreeDataNode.h @@ -121,7 +121,8 @@ namespace octomap { /// pointer to array of children, may be NULL /// @note The tree class manages this pointer, the array, and the memory for it! - void** children; + /// The children of a node are always enforced to be the same type as the node + AbstractOcTreeNode** children; /// stored data (payload) T value; diff --git a/octomap/include/octomap/OcTreeDataNode.hxx b/octomap/include/octomap/OcTreeDataNode.hxx index 81fedb59..14984083 100644 --- a/octomap/include/octomap/OcTreeDataNode.hxx +++ b/octomap/include/octomap/OcTreeDataNode.hxx @@ -129,7 +129,7 @@ namespace octomap { // ============================================================ template void OcTreeDataNode::allocChildren() { - children = new void*[8]; + children = new AbstractOcTreeNode*[8]; for (unsigned int i=0; i<8; i++) { children[i] = NULL; } diff --git a/octomap/valgrind_memcheck.supp b/octomap/valgrind_memcheck.supp index 8c8d0378..891166b6 100644 --- a/octomap/valgrind_memcheck.supp +++ b/octomap/valgrind_memcheck.supp @@ -2,7 +2,7 @@ # Suppresses the "leaks" by the static member initializer which cannot be avoided. # # You can run valgrind on an OctoMap binary (e.g. a unit test) with: -# valgrind --tool=memcheck --leak-check=full --suppressions=valgrind_memcheck.supp bin/test_.... +# valgrind --tool=memcheck --leak-check=full --show-leak-kinds=all --suppressions=valgrind_memcheck.supp bin/test_.... # { From 9887ea9d4d41c0242b44644738c9ba8548872cca Mon Sep 17 00:00:00 2001 From: Christoph Date: Sat, 26 Mar 2016 14:34:10 +0100 Subject: [PATCH 10/28] adding debug output for dynamic_edt CMakeLists.txt --- dynamicEDT3D/CMakeLists.txt | 3 +++ 1 file changed, 3 insertions(+) diff --git a/dynamicEDT3D/CMakeLists.txt b/dynamicEDT3D/CMakeLists.txt index 96f6ea1c..ef22d293 100644 --- a/dynamicEDT3D/CMakeLists.txt +++ b/dynamicEDT3D/CMakeLists.txt @@ -50,6 +50,9 @@ find_package(octomap REQUIRED HINTS ${CMAKE_SOURCE_DIR}/lib/cmake/octomap ${CMAKE_SOURCE_DIR}/../octomap/lib/cmake/octomap ) +MESSAGE(STATUS "Found octomap version: " ${octomap_VERSION}) +MESSAGE(STATUS "octomap libraries: ${OCTOMAP_LIBRARIES}") + INCLUDE_DIRECTORIES(${OCTOMAP_INCLUDE_DIRS}) ADD_SUBDIRECTORY(src) From b652c4c7dd38d886f8ba298f6e585edecd488b4e Mon Sep 17 00:00:00 2001 From: Armin Hornung Date: Sat, 26 Mar 2016 14:57:59 +0100 Subject: [PATCH 11/28] Fix instructions in release script --- increase_version.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/increase_version.py b/increase_version.py index 8325f53b..472bf214 100755 --- a/increase_version.py +++ b/increase_version.py @@ -103,7 +103,8 @@ print "Finished writing package.xml and CMakeLists.txt files.\n" print "Now check the output, adjust CHANGELOG, and \"git commit\".\nFinally, run:" print " git checkout master && git merge --no-ff devel && git tag v%s" % new_version_str - print " git push && git push --tags" + print " git push origin master devel && git push --tags" + print "\n(adjust when not on the \"devel\" branch)\n" From aa58bd5606104c114ee8f83c0c402ce5fa937fc6 Mon Sep 17 00:00:00 2001 From: Armin Hornung Date: Tue, 5 Apr 2016 20:35:24 +0200 Subject: [PATCH 12/28] Move hasChildren() / childExists(i) from OcTreeDataNode into OcTreeBaseImpl, now called nodeHasChildren(...) / nodeChildExists(...). Old functions now deprecated as last refactoring for #98. --- octomap/include/octomap/OcTreeBaseImpl.h | 13 ++++ octomap/include/octomap/OcTreeBaseImpl.hxx | 62 +++++++++++++------ octomap/include/octomap/OcTreeDataNode.h | 9 +-- octomap/include/octomap/OcTreeDataNode.hxx | 4 +- octomap/include/octomap/OcTreeIterator.hxx | 18 +++--- .../include/octomap/OccupancyOcTreeBase.hxx | 28 ++++----- octomap/src/ColorOcTree.cpp | 34 +++++----- octomap/src/OcTreeNode.cpp | 23 ++++--- octomap/src/testing/test_iterators.cpp | 10 +-- 9 files changed, 128 insertions(+), 73 deletions(-) diff --git a/octomap/include/octomap/OcTreeBaseImpl.h b/octomap/include/octomap/OcTreeBaseImpl.h index d56a35a5..619cbc6d 100644 --- a/octomap/include/octomap/OcTreeBaseImpl.h +++ b/octomap/include/octomap/OcTreeBaseImpl.h @@ -131,6 +131,19 @@ namespace octomap { /// and have the same occupancy value bool isNodeCollapsible(const NODE* node) const; + /** + * Safe test if node has a child at index childIdx. + * First tests if there are any children. Replaces node->childExists(...) + * \return true if the child at childIdx exists + */ + bool nodeChildExists(const NODE* node, unsigned int childIdx) const; + + /** + * Safe test if node has any children. Replaces node->hasChildren(...) + * \return true if node has at least one child + */ + bool nodeHasChildren(const NODE* node) const; + /** * Expands a node (reverse of pruning): All children are created and * their occupancy probability is set to the node's value. diff --git a/octomap/include/octomap/OcTreeBaseImpl.hxx b/octomap/include/octomap/OcTreeBaseImpl.hxx index 84bd6072..2a2e0a73 100644 --- a/octomap/include/octomap/OcTreeBaseImpl.hxx +++ b/octomap/include/octomap/OcTreeBaseImpl.hxx @@ -209,26 +209,48 @@ namespace octomap { bool OcTreeBaseImpl::isNodeCollapsible(const NODE* node) const{ // all children must exist, must not have children of // their own and have the same occupancy probability - if (!node->childExists(0)) + if (!nodeChildExists(node, 0)) return false; const NODE* firstChild = getNodeChild(node, 0); - if (firstChild->hasChildren()) + if (nodeHasChildren(firstChild)) return false; for (unsigned int i = 1; i<8; i++) { // comparison via getChild so that casts of derived classes ensure // that the right == operator gets called - if (!node->childExists(i) || getNodeChild(node, i)->hasChildren() || !(*(getNodeChild(node, i)) == *(firstChild))) + if (!nodeChildExists(node, i) || nodeHasChildren(getNodeChild(node, i)) || !(*(getNodeChild(node, i)) == *(firstChild))) return false; } return true; } + + template + bool OcTreeBaseImpl::nodeChildExists(const NODE* node, unsigned int childIdx) const{ + assert(childIdx < 8); + if ((node->children != NULL) && (node->children[childIdx] != NULL)) + return true; + else + return false; + } + + template + bool OcTreeBaseImpl::nodeHasChildren(const NODE* node) const { + if (node->children == NULL) + return false; + + for (unsigned int i = 0; i<8; i++){ + if (node->children[i] != NULL) + return true; + } + return false; + } + template void OcTreeBaseImpl::expandNode(NODE* node){ - assert(!node->hasChildren()); + assert(!nodeHasChildren(node)); for (unsigned int k=0; k<8; k++) { NODE* newNode = createNodeChild(node, k); @@ -257,7 +279,11 @@ namespace octomap { template void OcTreeBaseImpl::allocNodeChildren(NODE* node){ - node->allocChildren(); // TODO move here? + // TODO NODE* + node->children = new AbstractOcTreeNode*[8]; + for (unsigned int i=0; i<8; i++) { + node->children[i] = NULL; + } } @@ -422,13 +448,13 @@ namespace octomap { // follow nodes down to requested level (for diff = 0 it's the last level) for (int i=(tree_depth-1); i>=diff; --i) { unsigned int pos = computeChildIdx(key_at_depth, i); - if (curNode->childExists(pos)) { + if (nodeChildExists(curNode, pos)) { // cast needed: (nodes need to ensure it's the right pointer) curNode = getNodeChild(curNode, pos); } else { // we expected a child but did not get it // is the current node a leaf already? - if (!curNode->hasChildren()) { + if (!nodeHasChildren(curNode)) { // TODO similar check to nodeChildExists? return curNode; } else { // it is not, search failed @@ -654,9 +680,9 @@ namespace octomap { unsigned int pos = computeChildIdx(key, this->tree_depth-1-depth); - if (!node->childExists(pos)) { + if (!nodeChildExists(node, pos)) { // child does not exist, but maybe it's a pruned node? - if ((!node->hasChildren()) && (node != this->root)) { + if ((!nodeHasChildren(node)) && (node != this->root)) { // TODO double check for exists / root exception? // current node does not have children AND it's not the root node // -> expand pruned node expandNode(node); @@ -675,7 +701,7 @@ namespace octomap { this->deleteNodeChild(node, pos); this->tree_size-=1; this->size_changed = true; - if (!node->hasChildren()) + if (!nodeHasChildren(node)) return true; else{ node->updateOccupancyChildren(); // TODO: occupancy? @@ -693,7 +719,7 @@ namespace octomap { if (depth < max_depth) { for (unsigned int i=0; i<8; i++) { - if (node->childExists(i)) { + if (nodeChildExists(node, i)) { pruneRecurs(getNodeChild(node, i), depth+1, max_depth, num_pruned); } } @@ -719,14 +745,14 @@ namespace octomap { assert(node); // current node has no children => can be expanded - if (!node->hasChildren()){ + if (!nodeHasChildren(node)){ expandNode(node); tree_size +=8; size_changed = true; } // recursively expand children for (unsigned int i=0; i<8; i++) { - if (node->childExists(i)) { + if (nodeChildExists(node, i)) { // TODO double check (node != NULL) expandRecurs(getNodeChild(node, i), depth+1, max_depth); } } @@ -748,7 +774,7 @@ namespace octomap { // 1 bit for each children; 0: empty, 1: allocated std::bitset<8> children; for (unsigned int i=0; i<8; i++) { - if (node->childExists(i)) + if (nodeChildExists(node, i)) children[i] = 1; else children[i] = 0; @@ -999,9 +1025,9 @@ namespace octomap { template void OcTreeBaseImpl::calcNumNodesRecurs(NODE* node, size_t& num_nodes) const { assert (node); - if (node->hasChildren()) { + if (nodeHasChildren(node)) { for (unsigned int i=0; i<8; ++i) { - if (node->childExists(i)) { + if (nodeChildExists(node, i)) { num_nodes++; calcNumNodesRecurs(getNodeChild(node, i), num_nodes); } @@ -1066,12 +1092,12 @@ namespace octomap { size_t OcTreeBaseImpl::getNumLeafNodesRecurs(const NODE* parent) const { assert(parent); - if (!parent->hasChildren()) // this is a leaf -> terminate + if (!nodeHasChildren(parent)) // this is a leaf -> terminate return 1; size_t sum_leafs_children = 0; for (unsigned int i=0; i<8; ++i) { - if (parent->childExists(i)) { + if (nodeChildExists(parent, i)) { sum_leafs_children += getNumLeafNodesRecurs(getNodeChild(parent, i)); } } diff --git a/octomap/include/octomap/OcTreeDataNode.h b/octomap/include/octomap/OcTreeDataNode.h index 3d74d6b7..8c92c392 100644 --- a/octomap/include/octomap/OcTreeDataNode.h +++ b/octomap/include/octomap/OcTreeDataNode.h @@ -90,13 +90,14 @@ namespace octomap { // -- children ---------------------------------- - /// Safe test to check of the i-th child exists, - /// first tests if there are any children. + /// Test whether the i-th child exists. + /// @deprecated Replaced by tree->nodeChildExists(...) /// \return true if the i-th child exists - bool childExists(unsigned int i) const; + OCTOMAP_DEPRECATED(bool childExists(unsigned int i) const); + /// @deprecated Replaced by tree->nodeHasChildren(...) /// \return true if the node has at least one child - bool hasChildren() const; + OCTOMAP_DEPRECATED(bool hasChildren() const); /// @return value stored in the node T getValue() const{return value;}; diff --git a/octomap/include/octomap/OcTreeDataNode.hxx b/octomap/include/octomap/OcTreeDataNode.hxx index 14984083..7d288d22 100644 --- a/octomap/include/octomap/OcTreeDataNode.hxx +++ b/octomap/include/octomap/OcTreeDataNode.hxx @@ -51,7 +51,7 @@ namespace octomap { OcTreeDataNode::OcTreeDataNode(const OcTreeDataNode& rhs) : children(NULL), value(rhs.value) { - if (rhs.hasChildren()){ + if (rhs.children){ allocChildren(); for (unsigned i = 0; i<8; ++i){ if (rhs.children[i]) @@ -66,7 +66,7 @@ namespace octomap { { // Delete only own members. OcTree maintains tree structure and must have deleted // children already - assert(!hasChildren()); + assert(children == NULL); } template diff --git a/octomap/include/octomap/OcTreeIterator.hxx b/octomap/include/octomap/OcTreeIterator.hxx index 1aed9ca6..46b64c30 100644 --- a/octomap/include/octomap/OcTreeIterator.hxx +++ b/octomap/include/octomap/OcTreeIterator.hxx @@ -175,7 +175,7 @@ unsigned short int center_offset_key = tree->tree_max_val >> s.depth; // push on stack in reverse order for (int i=7; i>=0; --i) { - if (top.node->childExists(i)) { + if (tree->nodeChildExists(top.node,i)) { computeChildKey(i, center_offset_key, top.key, s.key); s.node = tree->getNodeChild(top.node, i); //OCTOMAP_DEBUG_STR("Current depth: " << int(top.depth) << " new: "<< int(s.depth) << " child#" << i <<" ptr: "<stack.top().node->hasChildren() || this->stack.top().depth == this->maxDepth); } + bool isLeaf() const{ + return (!this->tree->nodeHasChildren(this->stack.top().node) || this->stack.top().depth == this->maxDepth); + } }; /** @@ -296,8 +298,9 @@ this->stack.pop(); // skip forward to next leaf - while(!this->stack.empty() && this->stack.top().depth < this->maxDepth - && this->stack.top().node->hasChildren()) + while(!this->stack.empty() + && this->stack.top().depth < this->maxDepth + && this->tree->nodeHasChildren(this->stack.top().node)) { this->singleIncrement(); } @@ -409,8 +412,9 @@ this->stack.pop(); // skip forward to next leaf - while(!this->stack.empty() && this->stack.top().depth < this->maxDepth - && this->stack.top().node->hasChildren()) + while(!this->stack.empty() + && this->stack.top().depth < this->maxDepth + && this->tree->nodeHasChildren(this->stack.top().node)) { this->singleIncrement(); } @@ -434,7 +438,7 @@ unsigned short int center_offset_key = this->tree->tree_max_val >> s.depth; // push on stack in reverse order for (int i=7; i>=0; --i) { - if (top.node->childExists(i)) { + if (this->tree->nodeChildExists(top.node, i)) { computeChildKey(i, center_offset_key, top.key, s.key); // overlap of query bbx and child bbx? diff --git a/octomap/include/octomap/OccupancyOcTreeBase.hxx b/octomap/include/octomap/OccupancyOcTreeBase.hxx index badd60ee..b6fd4c86 100644 --- a/octomap/include/octomap/OccupancyOcTreeBase.hxx +++ b/octomap/include/octomap/OccupancyOcTreeBase.hxx @@ -373,9 +373,9 @@ namespace octomap { // follow down to last level if (depth < this->tree_depth) { unsigned int pos = computeChildIdx(key, this->tree_depth -1 - depth); - if (!node->childExists(pos)) { + if (!this->nodeChildExists(node, pos)) { // child does not exist, but maybe it's a pruned node? - if ((!node->hasChildren()) && !node_just_created ) { + if (!this->nodeHasChildren(node) && !node_just_created ) { // current node does not have children AND it is not a new node // -> expand pruned node this->expandNode(node); @@ -442,9 +442,9 @@ namespace octomap { // follow down to last level if (depth < this->tree_depth) { unsigned int pos = computeChildIdx(key, this->tree_depth -1 - depth); - if (!node->childExists(pos)) { + if (!this->nodeChildExists(node, pos)) { // child does not exist, but maybe it's a pruned node? - if ((!node->hasChildren()) && !node_just_created ) { + if (!this->nodeHasChildren(node) && !node_just_created ) { // current node does not have children AND it is not a new node // -> expand pruned node this->expandNode(node); @@ -511,11 +511,11 @@ namespace octomap { assert(node); // only recurse and update for inner nodes: - if (node->hasChildren()){ + if (this->nodeHasChildren(node)){ // return early for last level: if (depth < this->tree_depth){ for (unsigned int i=0; i<8; i++) { - if (node->childExists(i)) { + if (this->nodeChildExists(node, i)) { updateInnerOccupancyRecurs(this->getNodeChild(node, i), depth+1); } } @@ -546,7 +546,7 @@ namespace octomap { if (depth < max_depth) { for (unsigned int i=0; i<8; i++) { - if (node->childExists(i)) { + if (this->nodeChildExists(node, i)) { toMaxLikelihoodRecurs(this->getNodeChild(node, i), depth+1, max_depth); } } @@ -1019,7 +1019,7 @@ namespace octomap { // read children's children and set the label for (unsigned int i=0; i<8; i++) { - if (node->childExists(i)) { + if (this->nodeChildExists(node, i)) { NODE* child = this->getNodeChild(node, i); if (fabs(child->getLogOdds() + 200.)<1e-3) { readBinaryNode(s, child); @@ -1050,9 +1050,9 @@ namespace octomap { // can be one logic expression per bit for (unsigned int i=0; i<4; i++) { - if (node->childExists(i)) { + if (this->nodeChildExists(node, i)) { const NODE* child = this->getNodeChild(node, i); - if (child->hasChildren()) { child1to4[i*2] = 1; child1to4[i*2+1] = 1; } + if (this->nodeHasChildren(child)) { child1to4[i*2] = 1; child1to4[i*2+1] = 1; } else if (this->isNodeOccupied(child)) { child1to4[i*2] = 0; child1to4[i*2+1] = 1; } else { child1to4[i*2] = 1; child1to4[i*2+1] = 0; } } @@ -1062,9 +1062,9 @@ namespace octomap { } for (unsigned int i=0; i<4; i++) { - if (node->childExists(i+4)) { + if (this->nodeChildExists(node, i+4)) { const NODE* child = this->getNodeChild(node, i+4); - if (child->hasChildren()) { child5to8[i*2] = 1; child5to8[i*2+1] = 1; } + if (this->nodeHasChildren(child)) { child5to8[i*2] = 1; child5to8[i*2+1] = 1; } else if (this->isNodeOccupied(child)) { child5to8[i*2] = 0; child5to8[i*2+1] = 1; } else { child5to8[i*2] = 1; child5to8[i*2+1] = 0; } } @@ -1084,9 +1084,9 @@ namespace octomap { // write children's children for (unsigned int i=0; i<8; i++) { - if (node->childExists(i)) { + if (this->nodeChildExists(node, i)) { const NODE* child = this->getNodeChild(node, i); - if (child->hasChildren()) { + if (this->nodeHasChildren(child)) { writeBinaryNode(s, child); } } diff --git a/octomap/src/ColorOcTree.cpp b/octomap/src/ColorOcTree.cpp index dd72e909..943097cb 100644 --- a/octomap/src/ColorOcTree.cpp +++ b/octomap/src/ColorOcTree.cpp @@ -52,19 +52,25 @@ namespace octomap { } ColorOcTreeNode::Color ColorOcTreeNode::getAverageChildColor() const { - int mr(0), mg(0), mb(0); - int c(0); - for (int i=0; i<8; i++) { - ColorOcTreeNode* child = static_cast(children[i]); - - if (childExists(i) && child->isColorSet()) { - mr += child->getColor().r; - mg += child->getColor().g; - mb += child->getColor().b; - ++c; + int mr = 0; + int mg = 0; + int mb = 0; + int c = 0; + + if (children != NULL){ + for (int i=0; i<8; i++) { + ColorOcTreeNode* child = static_cast(children[i]); + + if (child != NULL && child->isColorSet()) { + mr += child->getColor().r; + mg += child->getColor().g; + mb += child->getColor().b; + ++c; + } } } - if (c) { + + if (c > 0) { mr /= c; mg /= c; mb /= c; @@ -123,7 +129,7 @@ namespace octomap { const unsigned char& r, const unsigned char& g, const unsigned char& b) { - ColorOcTreeNode* n = search (key); + ColorOcTreeNode* n = search(key); if (n != 0) { if (n->isColorSet()) { ColorOcTreeNode::Color prev_color = n->getColor(); @@ -167,11 +173,11 @@ namespace octomap { void ColorOcTree::updateInnerOccupancyRecurs(ColorOcTreeNode* node, unsigned int depth) { // only recurse and update for inner nodes: - if (node->hasChildren()){ + if (nodeHasChildren(node)){ // return early for last level: if (depth < this->tree_depth){ for (unsigned int i=0; i<8; i++) { - if (node->childExists(i)) { + if (nodeChildExists(node, i)) { updateInnerOccupancyRecurs(getNodeChild(node, i), depth+1); } } diff --git a/octomap/src/OcTreeNode.cpp b/octomap/src/OcTreeNode.cpp index 47d51bc5..17459f9a 100644 --- a/octomap/src/OcTreeNode.cpp +++ b/octomap/src/OcTreeNode.cpp @@ -57,10 +57,12 @@ namespace octomap { double OcTreeNode::getMeanChildLogOdds() const{ double mean = 0; char c = 0; - for (unsigned int i=0; i<8; i++) { - if (childExists(i)) { - mean += static_cast(children[i])->getOccupancy(); // TODO check if works generally - c++; + if (children !=NULL){ + for (unsigned int i=0; i<8; i++) { + if (children[i] != NULL) { + mean += static_cast(children[i])->getOccupancy(); // TODO check if works generally + ++c; + } } } @@ -72,11 +74,14 @@ namespace octomap { float OcTreeNode::getMaxChildLogOdds() const{ float max = -std::numeric_limits::max(); - for (unsigned int i=0; i<8; i++) { - if (childExists(i)) { - float l = static_cast(children[i])->getLogOdds(); // TODO check if works generally - if (l > max) - max = l; + + if (children !=NULL){ + for (unsigned int i=0; i<8; i++) { + if (children[i] != NULL) { + float l = static_cast(children[i])->getLogOdds(); // TODO check if works generally + if (l > max) + max = l; + } } } return max; diff --git a/octomap/src/testing/test_iterators.cpp b/octomap/src/testing/test_iterators.cpp index 623d4292..d14f87bb 100644 --- a/octomap/src/testing/test_iterators.cpp +++ b/octomap/src/testing/test_iterators.cpp @@ -42,13 +42,13 @@ void getLeafNodesRecurs(std::list& voxels, OcTree* tree, bool occupied) { if ((depth <= max_depth) && (node != NULL) ) { - if (node->hasChildren() && (depth != max_depth)) { + if (tree->nodeHasChildren(node) && (depth != max_depth)) { float center_offset = float(tree_center(0) / pow( 2., (double) depth+1)); point3d search_center; for (unsigned int i=0; i<8; i++) { - if (node->childExists(i)) { + if (tree->nodeChildExists(node, i)) { computeChildCenter(i, center_offset, parent_center, search_center); getLeafNodesRecurs(voxels, max_depth, tree->getNodeChild(node, i), depth+1, search_center, tree_center, tree, occupied); @@ -75,13 +75,13 @@ void getVoxelsRecurs(std::list& voxels, OcTree* tree){ if ((depth <= max_depth) && (node != NULL) ) { - if (node->hasChildren() && (depth != max_depth)) { + if (tree->nodeHasChildren(node) && (depth != max_depth)) { double center_offset = tree_center(0) / pow(2., (double) depth + 1); point3d search_center; for (unsigned int i = 0; i < 8; i++) { - if (node->childExists(i)) { + if (tree->nodeChildExists(node, i)) { computeChildCenter(i, (float) center_offset, parent_center, search_center); getVoxelsRecurs(voxels, max_depth, tree->getNodeChild(node, i), depth + 1, search_center, tree_center, tree); @@ -172,7 +172,7 @@ void boundingBoxTest(OcTree* tree){ count++; OcTreeKey currentKey = it.getKey(); // leaf is actually a leaf: - EXPECT_FALSE(it->hasChildren()); + EXPECT_FALSE(tree->nodeHasChildren(&(*it))); // leaf exists in tree: OcTreeNode* node = tree->search(currentKey); From 56af1f546331d13dce1e010250151c47980d299a Mon Sep 17 00:00:00 2001 From: Armin Hornung Date: Wed, 6 Apr 2016 21:10:47 +0200 Subject: [PATCH 13/28] Minor fixes from review --- octomap/include/octomap/OcTreeBaseImpl.hxx | 4 +--- octomap/include/octomap/OcTreeDataNode.hxx | 4 ++-- 2 files changed, 3 insertions(+), 5 deletions(-) diff --git a/octomap/include/octomap/OcTreeBaseImpl.hxx b/octomap/include/octomap/OcTreeBaseImpl.hxx index 2a2e0a73..e1d05ad1 100644 --- a/octomap/include/octomap/OcTreeBaseImpl.hxx +++ b/octomap/include/octomap/OcTreeBaseImpl.hxx @@ -66,9 +66,7 @@ namespace octomap { template OcTreeBaseImpl::~OcTreeBaseImpl(){ - if (root){ - deleteNodeRecurs(root); - } + clear(); } diff --git a/octomap/include/octomap/OcTreeDataNode.hxx b/octomap/include/octomap/OcTreeDataNode.hxx index 7d288d22..38256bf3 100644 --- a/octomap/include/octomap/OcTreeDataNode.hxx +++ b/octomap/include/octomap/OcTreeDataNode.hxx @@ -51,10 +51,10 @@ namespace octomap { OcTreeDataNode::OcTreeDataNode(const OcTreeDataNode& rhs) : children(NULL), value(rhs.value) { - if (rhs.children){ + if (rhs.children != NULL){ allocChildren(); for (unsigned i = 0; i<8; ++i){ - if (rhs.children[i]) + if (rhs.children[i] != NULL) children[i] = new OcTreeDataNode(*(static_cast*>(rhs.children[i]))); } From 9dd6bd78df2ef8cbc2a561ffd226a28bdb024539 Mon Sep 17 00:00:00 2001 From: Armin Hornung Date: Wed, 6 Apr 2016 21:11:09 +0200 Subject: [PATCH 14/28] Enable CountingOcTree in CMakeLists, fix with new node/tree implementation --- octomap/src/CMakeLists.txt | 2 +- octomap/src/CountingOcTree.cpp | 24 ++++++------------------ 2 files changed, 7 insertions(+), 19 deletions(-) diff --git a/octomap/src/CMakeLists.txt b/octomap/src/CMakeLists.txt index a03cd847..e0fd2eeb 100644 --- a/octomap/src/CMakeLists.txt +++ b/octomap/src/CMakeLists.txt @@ -3,7 +3,7 @@ SET (octomap_SRCS AbstractOccupancyOcTree.cpp Pointcloud.cpp ScanGraph.cpp -# CountingOcTree.cpp # deactivated for now (testing) + CountingOcTree.cpp OcTree.cpp OcTreeNode.cpp OcTreeStamped.cpp diff --git a/octomap/src/CountingOcTree.cpp b/octomap/src/CountingOcTree.cpp index 497e54a9..f981d5e3 100644 --- a/octomap/src/CountingOcTree.cpp +++ b/octomap/src/CountingOcTree.cpp @@ -48,18 +48,6 @@ namespace octomap { } - // TODO: move to tree - void CountingOcTreeNode::expandNode(){ - assert(!hasChildren()); - - // divide "counts" evenly to children - unsigned int childCount = (unsigned int)(value/ 8.0 +0.5); - for (unsigned int k=0; k<8; k++) { - createChild(k); - children[k]->setValue(childCount); - } - } - /// implementation of CountingOcTree -------------------------------------- CountingOcTree::CountingOcTree(double resolution) : OcTreeBase(resolution) { @@ -87,12 +75,12 @@ namespace octomap { unsigned int pos = computeChildIdx(k, i); // requested node does not exist - if (!curNode->childExists(pos)) { - curNode->createChild(pos); + if (!nodeChildExists(curNode, pos)) { + createNodeChild(curNode, pos); tree_size++; } // descent tree - curNode = static_cast (curNode->getChild(pos)); + curNode = getNodeChild(curNode, pos); curNode->increaseCount(); // modify traversed nodes } @@ -114,15 +102,15 @@ namespace octomap { CountingOcTreeNode* node, unsigned int depth, const OcTreeKey& parent_key) const { - if (depth < max_depth && node->hasChildren()) { + if (depth < max_depth && nodeHasChildren(node)) { unsigned short int center_offset_key = this->tree_max_val >> (depth + 1); OcTreeKey search_key; for (unsigned int i=0; i<8; ++i) { - if (node->childExists(i)) { + if (nodeChildExists(node,i)) { computeChildKey(i, center_offset_key, parent_key, search_key); - getCentersMinHitsRecurs(node_centers, min_hits, max_depth, node->getChild(i), depth+1, search_key); + getCentersMinHitsRecurs(node_centers, min_hits, max_depth, getNodeChild(node,i), depth+1, search_key); } } } From b5b039f0e21f0d6ef610b83e1ab65f7ad7f26c7b Mon Sep 17 00:00:00 2001 From: Armin Hornung Date: Mon, 11 Apr 2016 21:15:47 +0200 Subject: [PATCH 15/28] Extend test_pruning with manual OcTreeNode creation and deletion --- octomap/src/testing/test_pruning.cpp | 66 +++++++++++++++++++++++++++- 1 file changed, 65 insertions(+), 1 deletion(-) diff --git a/octomap/src/testing/test_pruning.cpp b/octomap/src/testing/test_pruning.cpp index b6409b77..6508b6f7 100644 --- a/octomap/src/testing/test_pruning.cpp +++ b/octomap/src/testing/test_pruning.cpp @@ -171,8 +171,72 @@ int main(int argc, char** argv) { } EXPECT_EQ(tree.calcNumNodes(), tree.size()); EXPECT_EQ(67, tree.size()); + + // test deletion / pruning of single nodes + { + std::cout << "\nCreating / deleting nodes\n===============================\n"; + size_t initialSize = tree.size(); + EXPECT_EQ(initialSize, tree.calcNumNodes()); + EXPECT_EQ(initialSize, 67); + + point3d newCoord(-2.0, -2.0, -2.0); + OcTreeNode* newNode = tree.updateNode(newCoord, true); + EXPECT_TRUE(newNode != NULL); + + size_t insertedSize = tree.size(); + std::cout << "Size after one insertion: " << insertedSize << std::endl; + EXPECT_EQ(insertedSize, tree.calcNumNodes()); + EXPECT_EQ(insertedSize, 83); + + // find parent of newly inserted node: + OcTreeNode* parentNode = tree.search(newCoord, tree.getTreeDepth() -1); + EXPECT_TRUE(parentNode); + EXPECT_TRUE(tree.nodeHasChildren(parentNode)); + + // only one child exists: + for (size_t i = 0; i < 7; ++i){ + EXPECT_FALSE(tree.nodeChildExists(parentNode, i)); + } + EXPECT_TRUE(tree.nodeChildExists(parentNode, 7)); + + // create another new node manually: + OcTreeNode* newNodeCreated = tree.createNodeChild(parentNode, 0); + EXPECT_TRUE(newNodeCreated != NULL); + EXPECT_TRUE(tree.nodeChildExists(parentNode, 0)); + const float value = 0.123f; + newNodeCreated->setValue(value); + tree.write("pruning_test_edited.ot"); + + // currently fails! + //EXPECT_EQ(tree.size(), tree.calcNumNodes()); + EXPECT_EQ(tree.calcNumNodes(), insertedSize+1); + tree.prune(); + EXPECT_EQ(tree.calcNumNodes(), insertedSize+1); + + tree.deleteNodeChild(parentNode, 0); + tree.deleteNodeChild(parentNode, 7); + + // currently fails! + //EXPECT_EQ(tree.size(), tree.calcNumNodes()); + EXPECT_EQ(tree.calcNumNodes(), insertedSize-1); + + tree.prune(); + //EXPECT_EQ(tree.size(), tree.calcNumNodes()); + EXPECT_EQ(tree.calcNumNodes(), insertedSize-1); + + tree.expandNode(parentNode); + //EXPECT_EQ(tree.size(), tree.calcNumNodes()); + EXPECT_EQ(tree.calcNumNodes(), insertedSize+7); + + + EXPECT_TRUE(tree.pruneNode(parentNode)); + //EXPECT_EQ(tree.size(), tree.calcNumNodes()); + EXPECT_EQ(tree.calcNumNodes(), insertedSize-1); + + + } - //tree.write("pruning_test_out.ot"); + tree.write("pruning_test_out.ot"); std::cerr << "Test successful.\n"; return 0; From c9511646341addd885c8b287683e22427603bc64 Mon Sep 17 00:00:00 2001 From: Armin Hornung Date: Mon, 11 Apr 2016 21:54:02 +0200 Subject: [PATCH 16/28] Fix ColorOcTree pruning, restore old behavior: ignore node color for pruning, only consider occupancy. Change isNodeCollapisble(...), expandNode(...), pruneNode(...) in OcTreeBaseImpl to virtual for this behavior. Extend test_color_tree unit test. --- octomap/include/octomap/ColorOcTree.h | 12 +++- octomap/include/octomap/OcTreeBaseImpl.h | 6 +- octomap/src/ColorOcTree.cpp | 22 ++++++- octomap/src/testing/test_color_tree.cpp | 80 ++++++++++++++++++++++-- 4 files changed, 108 insertions(+), 12 deletions(-) diff --git a/octomap/include/octomap/ColorOcTree.h b/octomap/include/octomap/ColorOcTree.h index 1b5a10bd..30f384e3 100644 --- a/octomap/include/octomap/ColorOcTree.h +++ b/octomap/include/octomap/ColorOcTree.h @@ -117,8 +117,16 @@ namespace octomap { std::string getTreeType() const {return "ColorOcTree";} - bool pruneNode(ColorOcTreeNode* node); - + /** + * Prunes a node when it is collapsible. This overloaded + * version only considers the node occupancy for pruning, + * different colors of child nodes are ignored. + * @return true if pruning was successful + */ + virtual bool pruneNode(ColorOcTreeNode* node); + + virtual bool isNodeCollapsible(const ColorOcTreeNode* node) const; + // set node color at given key or coordinate. Replaces previous color. ColorOcTreeNode* setNodeColor(const OcTreeKey& key, const unsigned char& r, const unsigned char& g, const unsigned char& b); diff --git a/octomap/include/octomap/OcTreeBaseImpl.h b/octomap/include/octomap/OcTreeBaseImpl.h index 619cbc6d..9ba1e4d7 100644 --- a/octomap/include/octomap/OcTreeBaseImpl.h +++ b/octomap/include/octomap/OcTreeBaseImpl.h @@ -129,7 +129,7 @@ namespace octomap { /// A node is collapsible if all children exist, don't have children of their own /// and have the same occupancy value - bool isNodeCollapsible(const NODE* node) const; + virtual bool isNodeCollapsible(const NODE* node) const; /** * Safe test if node has a child at index childIdx. @@ -152,13 +152,13 @@ namespace octomap { * leaf at the lowest level) * */ - void expandNode(NODE* node); + virtual void expandNode(NODE* node); /** * Prunes a node when it is collapsible * @return true if pruning was successful */ - bool pruneNode(NODE* node); + virtual bool pruneNode(NODE* node); // -------- diff --git a/octomap/src/ColorOcTree.cpp b/octomap/src/ColorOcTree.cpp index 943097cb..6e99625d 100644 --- a/octomap/src/ColorOcTree.cpp +++ b/octomap/src/ColorOcTree.cpp @@ -105,8 +105,7 @@ namespace octomap { } bool ColorOcTree::pruneNode(ColorOcTreeNode* node) { - assert(0); - if (!isNodeCollapsible(node)) // TODO: overload here, check occupancy only? + if (!isNodeCollapsible(node)) return false; // set value to children's values (all assumed equal) @@ -124,6 +123,25 @@ namespace octomap { return true; } + + bool ColorOcTree::isNodeCollapsible(const ColorOcTreeNode* node) const{ + // all children must exist, must not have children of + // their own and have the same occupancy probability + if (!nodeChildExists(node, 0)) + return false; + + const ColorOcTreeNode* firstChild = getNodeChild(node, 0); + if (nodeHasChildren(firstChild)) + return false; + + for (unsigned int i = 1; i<8; i++) { + // compare nodes only using their occupancy, ignoring color for pruning + if (!nodeChildExists(node, i) || nodeHasChildren(getNodeChild(node, i)) || !(getNodeChild(node, i)->getValue() == firstChild->getValue())) + return false; + } + + return true; + } ColorOcTreeNode* ColorOcTree::averageNodeColor(const OcTreeKey& key, const unsigned char& r, diff --git a/octomap/src/testing/test_color_tree.cpp b/octomap/src/testing/test_color_tree.cpp index 971e5f30..75e5f29b 100644 --- a/octomap/src/testing/test_color_tree.cpp +++ b/octomap/src/testing/test_color_tree.cpp @@ -27,7 +27,7 @@ int main(int argc, char** argv) { for (int z=-20; z<20; z++) { point3d endpoint ((float) x*0.05f+0.01f, (float) y*0.05f+0.01f, (float) z*0.05f+0.01f); ColorOcTreeNode* n = tree.updateNode(endpoint, true); - n->setColor(z*5+100,x*5+100,y*5+100); // set color to red + n->setColor(z*5+100,x*5+100,y*5+100); } } } @@ -48,7 +48,7 @@ int main(int argc, char** argv) { cout << endl; - + std::cout << "\nWriting to / from file\n===============================\n"; std::string filename ("simple_color_tree.ot"); std::cout << "Writing color tree to " << filename << std::endl; // write color tree @@ -65,10 +65,12 @@ int main(int argc, char** argv) { ColorOcTree* read_color_tree = dynamic_cast(read_tree); EXPECT_TRUE(read_color_tree); + EXPECT_TRUE(tree == *read_color_tree); - cout << "Performing some queries:" << endl; - + { + cout << "Performing some queries:" << endl; + // TODO: some more meaningful tests point3d query (0., 0., 0.); ColorOcTreeNode* result = tree.search (query); ColorOcTreeNode* result2 = read_color_tree->search (query); @@ -104,10 +106,78 @@ int main(int argc, char** argv) { print_query_info(query, result2); EXPECT_FALSE(result); EXPECT_FALSE(result2); - } delete read_tree; + read_tree = NULL; + + { + std::cout << "\nPruning / expansion\n===============================\n"; + size_t initialSize = tree.size(); + EXPECT_EQ(initialSize, tree.calcNumNodes()); + std::cout << "Initial size: " << tree.size() << std::endl; + + // tree should already be pruned during insertion: + tree.prune(); + EXPECT_EQ(initialSize, tree.size()); + EXPECT_EQ(initialSize, tree.calcNumNodes()); + + tree.expand(); + std::cout << "Size after expansion: " << tree.size() << std::endl; + EXPECT_EQ(tree.size(), tree.calcNumNodes()); + + // prune again, should be same as initial size + + tree.prune(); + EXPECT_EQ(initialSize, tree.size()); + EXPECT_EQ(initialSize, tree.calcNumNodes()); + + } + + // delete / create some nodes + { + std::cout << "\nCreating / deleting nodes\n===============================\n"; + size_t initialSize = tree.size(); + EXPECT_EQ(initialSize, tree.calcNumNodes()); + std::cout << "Initial size: " << initialSize << std::endl; + + point3d newCoord(-2.0, -2.0, -2.0); + ColorOcTreeNode* newNode = tree.updateNode(newCoord, true); + newNode->setColor(255,0,0); + EXPECT_TRUE(newNode != NULL); + + size_t insertedSize = tree.size(); + std::cout << "Size after one insertion: " << insertedSize << std::endl; + EXPECT_EQ(insertedSize, tree.calcNumNodes()); + + // find parent of newly inserted node: + ColorOcTreeNode* parentNode = tree.search(newCoord, tree.getTreeDepth() -1); + EXPECT_TRUE(parentNode); + EXPECT_TRUE(tree.nodeHasChildren(parentNode)); + + // only one child exists: + EXPECT_TRUE(tree.nodeChildExists(parentNode, 0)); + for (size_t i = 1; i < 8; ++i){ + EXPECT_FALSE(tree.nodeChildExists(parentNode, i)); + } + + tree.deleteNodeChild(parentNode, 0); + std::cout << "Size after deleting one child: " << tree.calcNumNodes() << std::endl; + // currently fails! + //EXPECT_EQ(tree.size(), tree.calcNumNodes()); + + tree.prune(); + std::cout << "Size after prune: " << tree.calcNumNodes() << std::endl; + + tree.expandNode(parentNode); + std::cout << "Size after expanding one node: " << tree.calcNumNodes() << std::endl; + + EXPECT_TRUE(tree.pruneNode(parentNode)); + std::cout << "Size after pruning one node: " << tree.calcNumNodes() << std::endl; + + EXPECT_TRUE(tree.write("simple_color_tree_ed.ot")); + + } return 0; } From 7ecace123dbfd115449dbd8f66fe0303ec39a87d Mon Sep 17 00:00:00 2001 From: Armin Hornung Date: Tue, 12 Apr 2016 21:23:10 +0200 Subject: [PATCH 17/28] Fix #117: update internal number of nodes (only) in createNodeChild(...) and deleteNodeChild(...), also set size_changed flag --- octomap/include/octomap/OcTreeBaseImpl.hxx | 17 +++++++------- .../include/octomap/OccupancyOcTreeBase.hxx | 10 --------- octomap/src/ColorOcTree.cpp | 2 +- octomap/src/CountingOcTree.cpp | 1 - octomap/src/testing/test_pruning.cpp | 22 +++++++++---------- 5 files changed, 20 insertions(+), 32 deletions(-) diff --git a/octomap/include/octomap/OcTreeBaseImpl.hxx b/octomap/include/octomap/OcTreeBaseImpl.hxx index e1d05ad1..9a7237cd 100644 --- a/octomap/include/octomap/OcTreeBaseImpl.hxx +++ b/octomap/include/octomap/OcTreeBaseImpl.hxx @@ -178,6 +178,10 @@ namespace octomap { assert (node->children[childIdx] == NULL); NODE* newNode = new NODE(); node->children[childIdx] = static_cast(newNode); + + tree_size++; + size_changed = true; + return newNode; } @@ -187,6 +191,9 @@ namespace octomap { assert(node->children[childIdx] != NULL); delete static_cast(node->children[childIdx]); // TODO delete check if empty node->children[childIdx] = NULL; + + tree_size--; + size_changed = true; } template @@ -684,8 +691,7 @@ namespace octomap { // current node does not have children AND it's not the root node // -> expand pruned node expandNode(node); - this->tree_size+=8; - this->size_changed = true; + // tree_size and size_changed adjusted in createNodeChild(...) } else { // no branch here, node does not exist return false; } @@ -697,8 +703,7 @@ namespace octomap { // TODO: lazy eval? // TODO delete check depth, what happens to inner nodes with children? this->deleteNodeChild(node, pos); - this->tree_size-=1; - this->size_changed = true; + if (!nodeHasChildren(node)) return true; else{ @@ -727,8 +732,6 @@ namespace octomap { // max level reached if (pruneNode(node)) { num_pruned++; - tree_size -= 8; - size_changed = true; } } } @@ -745,8 +748,6 @@ namespace octomap { // current node has no children => can be expanded if (!nodeHasChildren(node)){ expandNode(node); - tree_size +=8; - size_changed = true; } // recursively expand children for (unsigned int i=0; i<8; i++) { diff --git a/octomap/include/octomap/OccupancyOcTreeBase.hxx b/octomap/include/octomap/OccupancyOcTreeBase.hxx index b6fd4c86..e61eae04 100644 --- a/octomap/include/octomap/OccupancyOcTreeBase.hxx +++ b/octomap/include/octomap/OccupancyOcTreeBase.hxx @@ -379,14 +379,10 @@ namespace octomap { // current node does not have children AND it is not a new node // -> expand pruned node this->expandNode(node); - this->tree_size+=8; - this->size_changed = true; } else { // not a pruned node, create requested child this->createNodeChild(node, pos); - this->tree_size++; - this->size_changed = true; created_node = true; } } @@ -398,7 +394,6 @@ namespace octomap { // prune node if possible, otherwise set own probability // note: combining both did not lead to a speedup! if (this->pruneNode(node)){ - this->tree_size -= 8; // return pointer to current parent (pruned), the just updated node no longer exists retval = node; } else{ @@ -448,14 +443,10 @@ namespace octomap { // current node does not have children AND it is not a new node // -> expand pruned node this->expandNode(node); - this->tree_size+=8; - this->size_changed = true; } else { // not a pruned node, create requested child this->createNodeChild(node, pos); - this->tree_size++; - this->size_changed = true; created_node = true; } } @@ -467,7 +458,6 @@ namespace octomap { // prune node if possible, otherwise set own probability // note: combining both did not lead to a speedup! if (this->pruneNode(node)){ - this->tree_size -= 8; // return pointer to current parent (pruned), the just updated node no longer exists retval = node; } else{ diff --git a/octomap/src/ColorOcTree.cpp b/octomap/src/ColorOcTree.cpp index 6e99625d..aece0b00 100644 --- a/octomap/src/ColorOcTree.cpp +++ b/octomap/src/ColorOcTree.cpp @@ -116,7 +116,7 @@ namespace octomap { // delete children for (unsigned int i=0;i<8;i++) { - delete static_cast(node->children[i]); + deleteNodeChild(node, i); } delete[] node->children; node->children = NULL; diff --git a/octomap/src/CountingOcTree.cpp b/octomap/src/CountingOcTree.cpp index f981d5e3..1d962b13 100644 --- a/octomap/src/CountingOcTree.cpp +++ b/octomap/src/CountingOcTree.cpp @@ -77,7 +77,6 @@ namespace octomap { // requested node does not exist if (!nodeChildExists(curNode, pos)) { createNodeChild(curNode, pos); - tree_size++; } // descent tree curNode = getNodeChild(curNode, pos); diff --git a/octomap/src/testing/test_pruning.cpp b/octomap/src/testing/test_pruning.cpp index 6508b6f7..00ff44ca 100644 --- a/octomap/src/testing/test_pruning.cpp +++ b/octomap/src/testing/test_pruning.cpp @@ -207,31 +207,29 @@ int main(int argc, char** argv) { newNodeCreated->setValue(value); tree.write("pruning_test_edited.ot"); - // currently fails! - //EXPECT_EQ(tree.size(), tree.calcNumNodes()); - EXPECT_EQ(tree.calcNumNodes(), insertedSize+1); + EXPECT_EQ(tree.size(), tree.calcNumNodes()); + EXPECT_EQ(tree.size(), insertedSize+1); tree.prune(); EXPECT_EQ(tree.calcNumNodes(), insertedSize+1); tree.deleteNodeChild(parentNode, 0); tree.deleteNodeChild(parentNode, 7); - // currently fails! - //EXPECT_EQ(tree.size(), tree.calcNumNodes()); - EXPECT_EQ(tree.calcNumNodes(), insertedSize-1); + EXPECT_EQ(tree.size(), tree.calcNumNodes()); + EXPECT_EQ(tree.size(), insertedSize-1); tree.prune(); - //EXPECT_EQ(tree.size(), tree.calcNumNodes()); - EXPECT_EQ(tree.calcNumNodes(), insertedSize-1); + EXPECT_EQ(tree.size(), tree.calcNumNodes()); + EXPECT_EQ(tree.size(), insertedSize-1); tree.expandNode(parentNode); - //EXPECT_EQ(tree.size(), tree.calcNumNodes()); - EXPECT_EQ(tree.calcNumNodes(), insertedSize+7); + EXPECT_EQ(tree.size(), tree.calcNumNodes()); + EXPECT_EQ(tree.size(), insertedSize+7); EXPECT_TRUE(tree.pruneNode(parentNode)); - //EXPECT_EQ(tree.size(), tree.calcNumNodes()); - EXPECT_EQ(tree.calcNumNodes(), insertedSize-1); + EXPECT_EQ(tree.size(), tree.calcNumNodes()); + EXPECT_EQ(tree.size(), insertedSize-1); } From 041df736fb2d51c48ae016f537a4baec8b2ed617 Mon Sep 17 00:00:00 2001 From: Armin Hornung Date: Tue, 12 Apr 2016 21:39:37 +0200 Subject: [PATCH 18/28] Extending test_color_tree --- octomap/src/testing/test_color_tree.cpp | 29 +++++++++++++++++-------- 1 file changed, 20 insertions(+), 9 deletions(-) diff --git a/octomap/src/testing/test_color_tree.cpp b/octomap/src/testing/test_color_tree.cpp index 75e5f29b..0d76a8a3 100644 --- a/octomap/src/testing/test_color_tree.cpp +++ b/octomap/src/testing/test_color_tree.cpp @@ -46,6 +46,14 @@ int main(int argc, char** argv) { // set inner node colors tree.updateInnerOccupancy(); + // should already be pruned + EXPECT_EQ(tree.size(), tree.calcNumNodes()); + const size_t initialSize = tree.size(); + EXPECT_EQ(initialSize, 1034); + tree.prune(); + EXPECT_EQ(tree.size(), tree.calcNumNodes()); + EXPECT_EQ(initialSize, tree.size()); + cout << endl; std::cout << "\nWriting to / from file\n===============================\n"; @@ -113,7 +121,7 @@ int main(int argc, char** argv) { { std::cout << "\nPruning / expansion\n===============================\n"; - size_t initialSize = tree.size(); + EXPECT_EQ(initialSize, tree.size()); EXPECT_EQ(initialSize, tree.calcNumNodes()); std::cout << "Initial size: " << tree.size() << std::endl; @@ -146,8 +154,9 @@ int main(int argc, char** argv) { newNode->setColor(255,0,0); EXPECT_TRUE(newNode != NULL); - size_t insertedSize = tree.size(); + const size_t insertedSize = tree.size(); std::cout << "Size after one insertion: " << insertedSize << std::endl; + EXPECT_EQ(insertedSize, initialSize+6); EXPECT_EQ(insertedSize, tree.calcNumNodes()); // find parent of newly inserted node: @@ -162,18 +171,20 @@ int main(int argc, char** argv) { } tree.deleteNodeChild(parentNode, 0); - std::cout << "Size after deleting one child: " << tree.calcNumNodes() << std::endl; - // currently fails! - //EXPECT_EQ(tree.size(), tree.calcNumNodes()); + EXPECT_EQ(tree.size(), tree.calcNumNodes()); + EXPECT_EQ(tree.size(), insertedSize - 1); tree.prune(); - std::cout << "Size after prune: " << tree.calcNumNodes() << std::endl; + EXPECT_EQ(tree.size(), tree.calcNumNodes()); + EXPECT_EQ(tree.size(), insertedSize - 1); - tree.expandNode(parentNode); - std::cout << "Size after expanding one node: " << tree.calcNumNodes() << std::endl; + tree.expandNode(parentNode); + EXPECT_EQ(tree.size(), tree.calcNumNodes()); + EXPECT_EQ(tree.size(), insertedSize + 7); EXPECT_TRUE(tree.pruneNode(parentNode)); - std::cout << "Size after pruning one node: " << tree.calcNumNodes() << std::endl; + EXPECT_EQ(tree.size(), tree.calcNumNodes()); + EXPECT_EQ(tree.size(), insertedSize - 1); EXPECT_TRUE(tree.write("simple_color_tree_ed.ot")); From 06daa5c72164519bfec9d08e364b15976d1e2e04 Mon Sep 17 00:00:00 2001 From: Armin Hornung Date: Wed, 13 Apr 2016 21:49:03 +0200 Subject: [PATCH 19/28] Replace unsigned short int for key values with typedef key_type (=uint16_t) --- octomap/include/octomap/OcTreeBaseImpl.h | 14 +++++++------- octomap/include/octomap/OcTreeBaseImpl.hxx | 10 +++++----- octomap/include/octomap/OcTreeIterator.hxx | 4 ++-- octomap/include/octomap/OcTreeKey.h | 17 ++++++++++------- octomap/src/CountingOcTree.cpp | 2 +- 5 files changed, 25 insertions(+), 22 deletions(-) diff --git a/octomap/include/octomap/OcTreeBaseImpl.h b/octomap/include/octomap/OcTreeBaseImpl.h index 9ba1e4d7..f87c42a5 100644 --- a/octomap/include/octomap/OcTreeBaseImpl.h +++ b/octomap/include/octomap/OcTreeBaseImpl.h @@ -346,12 +346,12 @@ namespace octomap { // /// Converts from a single coordinate into a discrete key - inline unsigned short int coordToKey(double coordinate) const{ + inline key_type coordToKey(double coordinate) const{ return ((int) floor(resolution_factor * coordinate)) + tree_max_val; } /// Converts from a single coordinate into a discrete key at a given depth - unsigned short int coordToKey(double coordinate, unsigned depth) const; + key_type coordToKey(double coordinate, unsigned depth) const; /// Converts from a 3D coordinate into a 3D addressing key @@ -404,7 +404,7 @@ namespace octomap { * @param depth Target depth level for the new key * @return Key for the new depth level */ - unsigned short int adjustKeyAtDepth(unsigned short int key, unsigned int depth) const; + key_type adjustKeyAtDepth(key_type key, unsigned int depth) const; /** * Converts a 3D coordinate into a 3D OcTreeKey, with boundary checking. @@ -455,7 +455,7 @@ namespace octomap { * @param key discrete 16 bit adressing key, result * @return true if coordinate is within the octree bounds (valid), false otherwise */ - bool coordToKeyChecked(double coordinate, unsigned short int& key) const; + bool coordToKeyChecked(double coordinate, key_type& key) const; /** * Converts a single coordinate into a discrete addressing key, with boundary checking. @@ -465,15 +465,15 @@ namespace octomap { * @param key discrete 16 bit adressing key, result * @return true if coordinate is within the octree bounds (valid), false otherwise */ - bool coordToKeyChecked(double coordinate, unsigned depth, unsigned short int& key) const; + bool coordToKeyChecked(double coordinate, unsigned depth, key_type& key) const; /// converts from a discrete key at a given depth into a coordinate /// corresponding to the key's center - double keyToCoord(unsigned short int key, unsigned depth) const; + double keyToCoord(key_type key, unsigned depth) const; /// converts from a discrete key at the lowest tree level into a coordinate /// corresponding to the key's center - inline double keyToCoord(unsigned short int key) const{ + inline double keyToCoord(key_type key) const{ return (double( (int) key - (int) this->tree_max_val ) +0.5) * this->resolution; } diff --git a/octomap/include/octomap/OcTreeBaseImpl.hxx b/octomap/include/octomap/OcTreeBaseImpl.hxx index 9a7237cd..e90f6ebb 100644 --- a/octomap/include/octomap/OcTreeBaseImpl.hxx +++ b/octomap/include/octomap/OcTreeBaseImpl.hxx @@ -294,7 +294,7 @@ namespace octomap { template - inline unsigned short int OcTreeBaseImpl::coordToKey(double coordinate, unsigned depth) const{ + inline key_type OcTreeBaseImpl::coordToKey(double coordinate, unsigned depth) const{ assert (depth <= tree_depth); int keyval = ((int) floor(resolution_factor * coordinate)); @@ -307,7 +307,7 @@ namespace octomap { template - bool OcTreeBaseImpl::coordToKeyChecked(double coordinate, unsigned short int& keyval) const { + bool OcTreeBaseImpl::coordToKeyChecked(double coordinate, key_type& keyval) const { // scale to resolution and shift center for tree_max_val int scaled_coord = ((int) floor(resolution_factor * coordinate)) + tree_max_val; @@ -322,7 +322,7 @@ namespace octomap { template - bool OcTreeBaseImpl::coordToKeyChecked(double coordinate, unsigned depth, unsigned short int& keyval) const { + bool OcTreeBaseImpl::coordToKeyChecked(double coordinate, unsigned depth, key_type& keyval) const { // scale to resolution and shift center for tree_max_val int scaled_coord = ((int) floor(resolution_factor * coordinate)) + tree_max_val; @@ -381,7 +381,7 @@ namespace octomap { } template - unsigned short int OcTreeBaseImpl::adjustKeyAtDepth(unsigned short int key, unsigned int depth) const{ + key_type OcTreeBaseImpl::adjustKeyAtDepth(key_type key, unsigned int depth) const{ unsigned int diff = tree_depth - depth; if(diff == 0) @@ -391,7 +391,7 @@ namespace octomap { } template - double OcTreeBaseImpl::keyToCoord(unsigned short int key, unsigned depth) const{ + double OcTreeBaseImpl::keyToCoord(key_type key, unsigned depth) const{ assert(depth <= tree_depth); // root is centered on 0 = 0.0 diff --git a/octomap/include/octomap/OcTreeIterator.hxx b/octomap/include/octomap/OcTreeIterator.hxx index 46b64c30..fbdcde41 100644 --- a/octomap/include/octomap/OcTreeIterator.hxx +++ b/octomap/include/octomap/OcTreeIterator.hxx @@ -172,7 +172,7 @@ StackElement s; s.depth = top.depth +1; - unsigned short int center_offset_key = tree->tree_max_val >> s.depth; + key_type center_offset_key = tree->tree_max_val >> s.depth; // push on stack in reverse order for (int i=7; i>=0; --i) { if (tree->nodeChildExists(top.node,i)) { @@ -435,7 +435,7 @@ typename iterator_base::StackElement s; s.depth = top.depth +1; - unsigned short int center_offset_key = this->tree->tree_max_val >> s.depth; + key_type center_offset_key = this->tree->tree_max_val >> s.depth; // push on stack in reverse order for (int i=7; i>=0; --i) { if (this->tree->nodeChildExists(top.node, i)) { diff --git a/octomap/include/octomap/OcTreeKey.h b/octomap/include/octomap/OcTreeKey.h index 8e330426..44e0b69f 100644 --- a/octomap/include/octomap/OcTreeKey.h +++ b/octomap/include/octomap/OcTreeKey.h @@ -40,6 +40,7 @@ #include #include +#include /* Libc++ does not implement the TR1 namespace, all c++11 related functionality * is instead implemented in the std namespace. @@ -60,6 +61,8 @@ namespace octomap { + typedef uint16_t key_type; + /** * OcTreeKey is a container class for internal key addressing. The keys count the * number of cells (voxels) from the origin as discrete address of a voxel. @@ -69,7 +72,7 @@ namespace octomap { public: OcTreeKey () {} - OcTreeKey (unsigned short int a, unsigned short int b, unsigned short int c) + OcTreeKey (key_type a, key_type b, key_type c) { k[0] = a; k[1] = b; k[2] = c; } OcTreeKey(const OcTreeKey& other){ k[0] = other.k[0]; k[1] = other.k[1]; k[2] = other.k[2]; @@ -84,14 +87,14 @@ namespace octomap { k[0] = other.k[0]; k[1] = other.k[1]; k[2] = other.k[2]; return *this; } - const unsigned short int& operator[] (unsigned int i) const { + const key_type& operator[] (unsigned int i) const { return k[i]; } - unsigned short int& operator[] (unsigned int i) { + key_type& operator[] (unsigned int i) { return k[i]; } - unsigned short int k[3]; + key_type k[3]; /// Provides a hash function on Keys struct KeyHash{ @@ -167,7 +170,7 @@ namespace octomap { * @param[in] parent_key current (parent) key * @param[out] child_key computed child key */ - inline void computeChildKey (unsigned int pos, unsigned short int center_offset_key, + inline void computeChildKey (unsigned int pos, key_type center_offset_key, const OcTreeKey& parent_key, OcTreeKey& child_key) { // x-axis if (pos & 1) child_key[0] = parent_key[0] + center_offset_key; @@ -196,11 +199,11 @@ namespace octomap { * @param key input indexing key (at lowest resolution / level) * @return key corresponding to the input key at the given level */ - inline OcTreeKey computeIndexKey(unsigned short int level, const OcTreeKey& key) { + inline OcTreeKey computeIndexKey(key_type level, const OcTreeKey& key) { if (level == 0) return key; else { - unsigned short int mask = 65535 << level; + key_type mask = 65535 << level; OcTreeKey result = key; result[0] &= mask; result[1] &= mask; diff --git a/octomap/src/CountingOcTree.cpp b/octomap/src/CountingOcTree.cpp index 1d962b13..4a59c7d8 100644 --- a/octomap/src/CountingOcTree.cpp +++ b/octomap/src/CountingOcTree.cpp @@ -103,7 +103,7 @@ namespace octomap { if (depth < max_depth && nodeHasChildren(node)) { - unsigned short int center_offset_key = this->tree_max_val >> (depth + 1); + key_type center_offset_key = this->tree_max_val >> (depth + 1); OcTreeKey search_key; for (unsigned int i=0; i<8; ++i) { From 455f83cd25ffe841555dc4a22f0b007ad2f40324 Mon Sep 17 00:00:00 2001 From: Armin Hornung Date: Wed, 13 Apr 2016 22:16:55 +0200 Subject: [PATCH 20/28] Replace unsigned char with uint8_t in API. Clean up const refs to primitive types in ColorOcTree interface. --- octomap/include/octomap/ColorOcTree.h | 36 +++++++++++----------- octomap/include/octomap/OcTreeIterator.hxx | 14 ++++----- octomap/include/octomap/OcTreeKey.h | 16 +++++++--- octomap/src/ColorOcTree.cpp | 26 ++++++++-------- octomap/src/OcTreeNode.cpp | 5 +-- 5 files changed, 52 insertions(+), 45 deletions(-) diff --git a/octomap/include/octomap/ColorOcTree.h b/octomap/include/octomap/ColorOcTree.h index 30f384e3..c9d73afe 100644 --- a/octomap/include/octomap/ColorOcTree.h +++ b/octomap/include/octomap/ColorOcTree.h @@ -52,7 +52,7 @@ namespace octomap { class Color { public: Color() : r(255), g(255), b(255) {} - Color(unsigned char _r, unsigned char _g, unsigned char _b) + Color(uint8_t _r, uint8_t _g, uint8_t _b) : r(_r), g(_g), b(_b) {} inline bool operator== (const Color &other) const { return (r==other.r && g==other.g && b==other.b); @@ -60,7 +60,7 @@ namespace octomap { inline bool operator!= (const Color &other) const { return (r!=other.r || g!=other.g || b!=other.b); } - unsigned char r, g, b; + uint8_t r, g, b; }; public: @@ -79,7 +79,7 @@ namespace octomap { inline Color getColor() const { return color; } inline void setColor(Color c) {this->color = c; } - inline void setColor(unsigned char r, unsigned char g, unsigned char b) { + inline void setColor(uint8_t r, uint8_t g, uint8_t b) { this->color = Color(r,g,b); } @@ -128,36 +128,36 @@ namespace octomap { virtual bool isNodeCollapsible(const ColorOcTreeNode* node) const; // set node color at given key or coordinate. Replaces previous color. - ColorOcTreeNode* setNodeColor(const OcTreeKey& key, const unsigned char& r, - const unsigned char& g, const unsigned char& b); + ColorOcTreeNode* setNodeColor(const OcTreeKey& key, uint8_t r, + uint8_t g, uint8_t b); - ColorOcTreeNode* setNodeColor(const float& x, const float& y, - const float& z, const unsigned char& r, - const unsigned char& g, const unsigned char& b) { + ColorOcTreeNode* setNodeColor(float x, float y, + float z, uint8_t r, + uint8_t g, uint8_t b) { OcTreeKey key; if (!this->coordToKeyChecked(point3d(x,y,z), key)) return NULL; return setNodeColor(key,r,g,b); } // integrate color measurement at given key or coordinate. Average with previous color - ColorOcTreeNode* averageNodeColor(const OcTreeKey& key, const unsigned char& r, - const unsigned char& g, const unsigned char& b); + ColorOcTreeNode* averageNodeColor(const OcTreeKey& key, uint8_t r, + uint8_t g, uint8_t b); - ColorOcTreeNode* averageNodeColor(const float& x, const float& y, - const float& z, const unsigned char& r, - const unsigned char& g, const unsigned char& b) { + ColorOcTreeNode* averageNodeColor(float x, float y, + float z, uint8_t r, + uint8_t g, uint8_t b) { OcTreeKey key; if (!this->coordToKeyChecked(point3d(x,y,z), key)) return NULL; return averageNodeColor(key,r,g,b); } // integrate color measurement at given key or coordinate. Average with previous color - ColorOcTreeNode* integrateNodeColor(const OcTreeKey& key, const unsigned char& r, - const unsigned char& g, const unsigned char& b); + ColorOcTreeNode* integrateNodeColor(const OcTreeKey& key, uint8_t r, + uint8_t g, uint8_t b); - ColorOcTreeNode* integrateNodeColor(const float& x, const float& y, - const float& z, const unsigned char& r, - const unsigned char& g, const unsigned char& b) { + ColorOcTreeNode* integrateNodeColor(float x, float y, + float z, uint8_t r, + uint8_t g, uint8_t b) { OcTreeKey key; if (!this->coordToKeyChecked(point3d(x,y,z), key)) return NULL; return integrateNodeColor(key,r,g,b); diff --git a/octomap/include/octomap/OcTreeIterator.hxx b/octomap/include/octomap/OcTreeIterator.hxx index fbdcde41..afe520a6 100644 --- a/octomap/include/octomap/OcTreeIterator.hxx +++ b/octomap/include/octomap/OcTreeIterator.hxx @@ -52,7 +52,7 @@ * @param tree OcTreeBaseImpl on which the iterator is used on * @param depth Maximum depth to traverse the tree. 0 (default): unlimited */ - iterator_base(OcTreeBaseImpl const* tree, unsigned char depth=0) + iterator_base(OcTreeBaseImpl const* tree, uint8_t depth=0) : tree((tree && tree->root) ? tree : NULL), maxDepth(depth) { if (tree && maxDepth == 0) @@ -150,13 +150,13 @@ struct StackElement{ NodeType* node; OcTreeKey key; - unsigned char depth; + uint8_t depth; }; protected: OcTreeBaseImpl const* tree; ///< Octree this iterator is working on - unsigned char maxDepth; ///< Maximum depth for depth-limited queries + uint8_t maxDepth; ///< Maximum depth for depth-limited queries /// Internal recursion stack. Apparently a stack of vector works fastest here. std::stack > stack; @@ -213,7 +213,7 @@ * @param tree OcTreeBaseImpl on which the iterator is used on * @param depth Maximum depth to traverse the tree. 0 (default): unlimited */ - tree_iterator(OcTreeBaseImpl const* tree, unsigned char depth=0) : iterator_base(tree, depth) {}; + tree_iterator(OcTreeBaseImpl const* tree, uint8_t depth=0) : iterator_base(tree, depth) {}; /// postfix increment operator of iterator (it++) tree_iterator operator++(int){ @@ -270,7 +270,7 @@ * @param tree OcTreeBaseImpl on which the iterator is used on * @param depth Maximum depth to traverse the tree. 0 (default): unlimited */ - leaf_iterator(OcTreeBaseImpl const* tree, unsigned char depth=0) : iterator_base(tree, depth) { + leaf_iterator(OcTreeBaseImpl const* tree, uint8_t depth=0) : iterator_base(tree, depth) { // tree could be empty (= no stack) if (this->stack.size() > 0){ // skip forward to next valid leaf node: @@ -350,7 +350,7 @@ * @param max Maximum point3d of the axis-aligned boundingbox * @param depth Maximum depth to traverse the tree. 0 (default): unlimited */ - leaf_bbx_iterator(OcTreeBaseImpl const* tree, const point3d& min, const point3d& max, unsigned char depth=0) + leaf_bbx_iterator(OcTreeBaseImpl const* tree, const point3d& min, const point3d& max, uint8_t depth=0) : iterator_base(tree, depth) { if (this->stack.size() > 0){ @@ -378,7 +378,7 @@ * @param max Maximum OcTreeKey to be included in the axis-aligned boundingbox * @param depth Maximum depth to traverse the tree. 0 (default): unlimited */ - leaf_bbx_iterator(OcTreeBaseImpl const* tree, const OcTreeKey& min, const OcTreeKey& max, unsigned char depth=0) + leaf_bbx_iterator(OcTreeBaseImpl const* tree, const OcTreeKey& min, const OcTreeKey& max, uint8_t depth=0) : iterator_base(tree, depth), minKey(min), maxKey(max) { // tree could be empty (= no stack) diff --git a/octomap/include/octomap/OcTreeKey.h b/octomap/include/octomap/OcTreeKey.h index 44e0b69f..69ac403a 100644 --- a/octomap/include/octomap/OcTreeKey.h +++ b/octomap/include/octomap/OcTreeKey.h @@ -184,11 +184,17 @@ namespace octomap { } /// generate child index (between 0 and 7) from key at given tree depth - inline unsigned char computeChildIdx(const OcTreeKey& key, int depth){ - unsigned char pos = 0; - if (key.k[0] & (1 << depth)) pos += 1; - if (key.k[1] & (1 << depth)) pos += 2; - if (key.k[2] & (1 << depth)) pos += 4; + inline uint8_t computeChildIdx(const OcTreeKey& key, int depth){ + uint8_t pos = 0; + if (key.k[0] & (1 << depth)) + pos += 1; + + if (key.k[1] & (1 << depth)) + pos += 2; + + if (key.k[2] & (1 << depth)) + pos += 4; + return pos; } diff --git a/octomap/src/ColorOcTree.cpp b/octomap/src/ColorOcTree.cpp index aece0b00..fb541b17 100644 --- a/octomap/src/ColorOcTree.cpp +++ b/octomap/src/ColorOcTree.cpp @@ -74,7 +74,7 @@ namespace octomap { mr /= c; mg /= c; mb /= c; - return Color((unsigned char) mr, (unsigned char) mg, (unsigned char) mb); + return Color((uint8_t) mr, (uint8_t) mg, (uint8_t) mb); } else { // no child had a color other than white return Color(255, 255, 255); @@ -94,9 +94,9 @@ namespace octomap { }; ColorOcTreeNode* ColorOcTree::setNodeColor(const OcTreeKey& key, - const unsigned char& r, - const unsigned char& g, - const unsigned char& b) { + uint8_t r, + uint8_t g, + uint8_t b) { ColorOcTreeNode* n = search (key); if (n != 0) { n->setColor(r, g, b); @@ -144,9 +144,9 @@ namespace octomap { } ColorOcTreeNode* ColorOcTree::averageNodeColor(const OcTreeKey& key, - const unsigned char& r, - const unsigned char& g, - const unsigned char& b) { + uint8_t r, + uint8_t g, + uint8_t b) { ColorOcTreeNode* n = search(key); if (n != 0) { if (n->isColorSet()) { @@ -161,19 +161,19 @@ namespace octomap { } ColorOcTreeNode* ColorOcTree::integrateNodeColor(const OcTreeKey& key, - const unsigned char& r, - const unsigned char& g, - const unsigned char& b) { + uint8_t r, + uint8_t g, + uint8_t b) { ColorOcTreeNode* n = search (key); if (n != 0) { if (n->isColorSet()) { ColorOcTreeNode::Color prev_color = n->getColor(); double node_prob = n->getOccupancy(); - unsigned char new_r = (unsigned char) ((double) prev_color.r * node_prob + uint8_t new_r = (uint8_t) ((double) prev_color.r * node_prob + (double) r * (0.99-node_prob)); - unsigned char new_g = (unsigned char) ((double) prev_color.g * node_prob + uint8_t new_g = (uint8_t) ((double) prev_color.g * node_prob + (double) g * (0.99-node_prob)); - unsigned char new_b = (unsigned char) ((double) prev_color.b * node_prob + uint8_t new_b = (uint8_t) ((double) prev_color.b * node_prob + (double) b * (0.99-node_prob)); n->setColor(new_r, new_g, new_b); } diff --git a/octomap/src/OcTreeNode.cpp b/octomap/src/OcTreeNode.cpp index 17459f9a..dfeb5490 100644 --- a/octomap/src/OcTreeNode.cpp +++ b/octomap/src/OcTreeNode.cpp @@ -36,6 +36,7 @@ #include #include #include +#include #include @@ -56,7 +57,7 @@ namespace octomap { double OcTreeNode::getMeanChildLogOdds() const{ double mean = 0; - char c = 0; + uint8_t c = 0; if (children !=NULL){ for (unsigned int i=0; i<8; i++) { if (children[i] != NULL) { @@ -66,7 +67,7 @@ namespace octomap { } } - if (c) + if (c > 0) mean /= (double) c; return log(mean/(1-mean)); From 8b8ac8ad981fe7c44f66db982afb4ac8cf1a7567 Mon Sep 17 00:00:00 2001 From: Armin Hornung Date: Thu, 14 Apr 2016 22:12:28 +0200 Subject: [PATCH 21/28] Extend valgrind suppression file to account for release (optimized) libs --- octomap/valgrind_memcheck.supp | 76 ++++++++++++++++++++++++++++++++-- 1 file changed, 73 insertions(+), 3 deletions(-) diff --git a/octomap/valgrind_memcheck.supp b/octomap/valgrind_memcheck.supp index 891166b6..e4c44ebc 100644 --- a/octomap/valgrind_memcheck.supp +++ b/octomap/valgrind_memcheck.supp @@ -15,14 +15,13 @@ fun:_ZNSsC1EPKcRKSaIcE fun:_ZNK7octomap*getTreeTypeEv fun:_ZN7octomap14AbstractOcTree16registerTreeTypeEPS0_ - fun:_ZN7octomap*StaticMemberInitializerC1Ev - fun:_Z41__static_initialization_and_destruction_0ii - fun:_GLOBAL__sub_I_*.cpp + ... fun:call_init.part.0 fun:call_init fun:_dl_init obj:/lib/x86_64-linux-gnu/ld-2.19.so } + { static_member_init_class_id_mapping Memcheck:Leak @@ -38,6 +37,33 @@ obj:/lib/x86_64-linux-gnu/ld-2.19.so } + +{ + static_member_init_class_id_mapping_opt + Memcheck:Leak + match-leak-kinds: reachable + fun:_Znwm + fun:_ZN7octomap14AbstractOcTree14classIDMappingEv + fun:_ZN7octomap14AbstractOcTree16registerTreeTypeEPS0_ + fun:call_init.part.0 + fun:call_init + fun:_dl_init + obj:/lib/x86_64-linux-gnu/ld-2.19.so +} + +{ + global_sub_opt + Memcheck:Leak + match-leak-kinds: reachable + fun:_Znwm + ... + fun:_GLOBAL__sub_I_*.cpp + fun:call_init.part.0 + fun:call_init + fun:_dl_init + obj:/lib/x86_64-linux-gnu/ld-2.19.so +} + { static_member_init_hash_tree Memcheck:Leak @@ -56,6 +82,19 @@ fun:_GLOBAL__sub_I_*.cpp } +{ + static_member_init_hash_tree_opt + Memcheck:Leak + match-leak-kinds: reachable + fun:_Znwm + fun:_ZNSt8_Rb_treeISsSt4pairIKSsPN7octomap14AbstractOcTreeEESt10_Select1stIS5_ESt4lessISsESaIS5_EE17_M_insert_unique_ESt23_Rb_tree_const_iteratorIS5_ERKS5_ + fun:_ZN7octomap14AbstractOcTree16registerTreeTypeEPS0_ + fun:call_init.part.0 + fun:call_init + fun:_dl_init + obj:/lib/x86_64-linux-gnu/ld-2.19.so +} + { static_member_init_keyhash Memcheck:Leak @@ -92,6 +131,22 @@ fun:_Z41__static_initialization_and_destruction_0ii } +{ + static_member_init_keyray_opt + Memcheck:Leak + match-leak-kinds: reachable + fun:_Znwm + fun:_ZNSt6vectorIN7octomap6KeyRayESaIS1_EE14_M_fill_insertEN9__gnu_cxx17__normal_iteratorIPS1_S3_EEmRKS1_ + ... + fun:_ZN7octomap*C1Ed + fun:_GLOBAL__sub_I_*.cpp + fun:call_init.part.0 + fun:call_init + fun:_dl_init + obj:/lib/x86_64-linux-gnu/ld-2.19.so +} + + { static_member_init_keyray2 Memcheck:Leak @@ -110,5 +165,20 @@ fun:_ZN7octomap*StaticMemberInitializerC1Ev } +{ + static_member_init_keyray2_opt + Memcheck:Leak + match-leak-kinds: reachable + fun:_Znwm + fun:_ZNSt6vectorIdSaIdEE14_M_fill_insertEN9__gnu_cxx17__normal_iteratorIPdS1_EEmRKd + fun:_ZN7octomap*INS_*EEC1Ed + fun:_ZN7octomap*C1Ed + fun:_GLOBAL__sub_I_*.cpp + fun:call_init.part.0 + fun:call_init + fun:_dl_init + obj:/lib/x86_64-linux-gnu/ld-2.19.so +} + From 775519d0f91d486cf5d8b1c3db084d55c1c5c8ab Mon Sep 17 00:00:00 2001 From: Armin Hornung Date: Fri, 15 Apr 2016 23:53:09 +0200 Subject: [PATCH 22/28] Cleanup of OcTreeKey and KeyRay, add KeyRay copy c'tor for vector insertion --- octomap/include/octomap/OcTreeKey.h | 35 ++++++++++++++++++++++------- 1 file changed, 27 insertions(+), 8 deletions(-) diff --git a/octomap/include/octomap/OcTreeKey.h b/octomap/include/octomap/OcTreeKey.h index 69ac403a..26ebc980 100644 --- a/octomap/include/octomap/OcTreeKey.h +++ b/octomap/include/octomap/OcTreeKey.h @@ -72,24 +72,35 @@ namespace octomap { public: OcTreeKey () {} - OcTreeKey (key_type a, key_type b, key_type c) - { k[0] = a; k[1] = b; k[2] = c; } + OcTreeKey (key_type a, key_type b, key_type c){ + k[0] = a; + k[1] = b; + k[2] = c; + } + OcTreeKey(const OcTreeKey& other){ - k[0] = other.k[0]; k[1] = other.k[1]; k[2] = other.k[2]; + k[0] = other.k[0]; + k[1] = other.k[1]; + k[2] = other.k[2]; } + bool operator== (const OcTreeKey &other) const { return ((k[0] == other[0]) && (k[1] == other[1]) && (k[2] == other[2])); } + bool operator!= (const OcTreeKey& other) const { return( (k[0] != other[0]) || (k[1] != other[1]) || (k[2] != other[2]) ); } + OcTreeKey& operator=(const OcTreeKey& other){ k[0] = other.k[0]; k[1] = other.k[1]; k[2] = other.k[2]; return *this; } + const key_type& operator[] (unsigned int i) const { return k[i]; } + key_type& operator[] (unsigned int i) { return k[i]; } @@ -128,20 +139,28 @@ namespace octomap { public: KeyRay () { - ray.resize(100000); + ray.resize(maxSize); reset(); } + + KeyRay(const KeyRay& other){ + ray = other.ray; + size_t dSize = other.end() - other.begin(); + end_of_ray = ray.begin() + dSize; + } + void reset() { end_of_ray = begin(); } + void addKey(const OcTreeKey& k) { assert(end_of_ray != ray.end()); *end_of_ray = k; - end_of_ray++; + ++end_of_ray; } size_t size() const { return end_of_ray - ray.begin(); } - size_t sizeMax() const { return 100000; } + size_t sizeMax() const { return maxSize; } typedef std::vector::iterator iterator; typedef std::vector::const_iterator const_iterator; @@ -155,10 +174,10 @@ namespace octomap { reverse_iterator rbegin() { return (reverse_iterator) end_of_ray; } reverse_iterator rend() { return ray.rend(); } - public: - + private: std::vector ray; std::vector::iterator end_of_ray; + const static size_t maxSize = 100000; }; /** From 03808e75793a45f38d39507301d7a89f795ec568 Mon Sep 17 00:00:00 2001 From: Armin Hornung Date: Sat, 16 Apr 2016 16:04:20 +0200 Subject: [PATCH 23/28] Add clearKeyRays method to OcTreeBaseImpl, called from StaticMemberInitializer to minimize unneeded memory (#102) --- octomap/include/octomap/ColorOcTree.h | 1 + octomap/include/octomap/CountingOcTree.h | 1 + octomap/include/octomap/OcTree.h | 1 + octomap/include/octomap/OcTreeBaseImpl.h | 8 ++++++++ octomap/include/octomap/OcTreeBaseImpl.hxx | 2 +- octomap/include/octomap/OcTreeStamped.h | 1 + octomap/valgrind_memcheck.supp | 4 ++-- 7 files changed, 15 insertions(+), 3 deletions(-) diff --git a/octomap/include/octomap/ColorOcTree.h b/octomap/include/octomap/ColorOcTree.h index c9d73afe..2d59643f 100644 --- a/octomap/include/octomap/ColorOcTree.h +++ b/octomap/include/octomap/ColorOcTree.h @@ -183,6 +183,7 @@ namespace octomap { public: StaticMemberInitializer() { ColorOcTree* tree = new ColorOcTree(0.1); + tree->clearKeyRays(); AbstractOcTree::registerTreeType(tree); } diff --git a/octomap/include/octomap/CountingOcTree.h b/octomap/include/octomap/CountingOcTree.h index 508f7075..e37ac81d 100644 --- a/octomap/include/octomap/CountingOcTree.h +++ b/octomap/include/octomap/CountingOcTree.h @@ -101,6 +101,7 @@ namespace octomap { public: StaticMemberInitializer() { CountingOcTree* tree = new CountingOcTree(0.1); + tree->clearKeyRays(); AbstractOcTree::registerTreeType(tree); } diff --git a/octomap/include/octomap/OcTree.h b/octomap/include/octomap/OcTree.h index 5e11e418..85cc0502 100644 --- a/octomap/include/octomap/OcTree.h +++ b/octomap/include/octomap/OcTree.h @@ -80,6 +80,7 @@ namespace octomap { public: StaticMemberInitializer() { OcTree* tree = new OcTree(0.1); + tree->clearKeyRays(); AbstractOcTree::registerTreeType(tree); } diff --git a/octomap/include/octomap/OcTreeBaseImpl.h b/octomap/include/octomap/OcTreeBaseImpl.h index f87c42a5..43517317 100644 --- a/octomap/include/octomap/OcTreeBaseImpl.h +++ b/octomap/include/octomap/OcTreeBaseImpl.h @@ -112,6 +112,14 @@ namespace octomap { inline double getNodeSize(unsigned depth) const {assert(depth <= tree_depth); return sizeLookupTable[depth];} + /** + * Clear KeyRay vector to minimize unneeded memory. This is only + * useful for the StaticMemberInitializer classes, don't call it for + * an octree that is actually used. + */ + void clearKeyRays(){ + keyrays.clear(); + } // -- Tree structure operations formerly contained in the nodes --- diff --git a/octomap/include/octomap/OcTreeBaseImpl.hxx b/octomap/include/octomap/OcTreeBaseImpl.hxx index e90f6ebb..e1614bca 100644 --- a/octomap/include/octomap/OcTreeBaseImpl.hxx +++ b/octomap/include/octomap/OcTreeBaseImpl.hxx @@ -62,7 +62,7 @@ namespace octomap { // no longer create an empty root node - only on demand } - + template OcTreeBaseImpl::~OcTreeBaseImpl(){ diff --git a/octomap/include/octomap/OcTreeStamped.h b/octomap/include/octomap/OcTreeStamped.h index 4ad9c3ef..10736f48 100644 --- a/octomap/include/octomap/OcTreeStamped.h +++ b/octomap/include/octomap/OcTreeStamped.h @@ -107,6 +107,7 @@ namespace octomap { public: StaticMemberInitializer() { OcTreeStamped* tree = new OcTreeStamped(0.1); + tree->clearKeyRays(); AbstractOcTree::registerTreeType(tree); } diff --git a/octomap/valgrind_memcheck.supp b/octomap/valgrind_memcheck.supp index e4c44ebc..67614c45 100644 --- a/octomap/valgrind_memcheck.supp +++ b/octomap/valgrind_memcheck.supp @@ -148,7 +148,7 @@ { - static_member_init_keyray2 + static_member_init_sizeLookupTable Memcheck:Leak match-leak-kinds: reachable fun:_Znwm @@ -166,7 +166,7 @@ } { - static_member_init_keyray2_opt + static_member_init_sizeLookupTable_opt Memcheck:Leak match-leak-kinds: reachable fun:_Znwm From 8db7cafce149c33a0850baa2a1f64f27b644da14 Mon Sep 17 00:00:00 2001 From: Armin Hornung Date: Sun, 17 Apr 2016 17:29:31 +0200 Subject: [PATCH 24/28] Cleanup: remove unused and unmaintained OcTreeLUT / OcTreeBaseSE classes --- octomap/include/octomap/OcTreeBaseSE.h | 80 --- octomap/include/octomap/OcTreeBaseSE.hxx | 192 ------- octomap/include/octomap/OcTreeLUT.h | 107 ---- octomap/include/octomap/OcTreeLUTdefs.h | 157 ------ octomap/src/CMakeLists.txt | 7 - octomap/src/OcTreeLUT.cpp | 613 ----------------------- octomap/src/testing/CMakeLists.txt | 3 - octomap/src/testing/test_lut.cpp | 67 --- 8 files changed, 1226 deletions(-) delete mode 100644 octomap/include/octomap/OcTreeBaseSE.h delete mode 100644 octomap/include/octomap/OcTreeBaseSE.hxx delete mode 100644 octomap/include/octomap/OcTreeLUT.h delete mode 100644 octomap/include/octomap/OcTreeLUTdefs.h delete mode 100644 octomap/src/OcTreeLUT.cpp delete mode 100644 octomap/src/testing/test_lut.cpp diff --git a/octomap/include/octomap/OcTreeBaseSE.h b/octomap/include/octomap/OcTreeBaseSE.h deleted file mode 100644 index a9193384..00000000 --- a/octomap/include/octomap/OcTreeBaseSE.h +++ /dev/null @@ -1,80 +0,0 @@ -/* - * OctoMap - An Efficient Probabilistic 3D Mapping Framework Based on Octrees - * http://octomap.github.com/ - * - * Copyright (c) 2009-2013, K.M. Wurm and A. Hornung, University of Freiburg - * All rights reserved. - * License: New BSD - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in the - * documentation and/or other materials provided with the distribution. - * * Neither the name of the University of Freiburg nor the names of its - * contributors may be used to endorse or promote products derived from - * this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - */ - -#ifndef OCTOMAP_OCTREE_BASE_SE_H -#define OCTOMAP_OCTREE_BASE_SE_H - - -#include "OcTreeBase.h" -#include "OcTreeLUT.h" - - -namespace octomap { - - - template - class OcTreeBaseSE: public OcTreeBase { - - public: - - OcTreeBaseSE(double _resolution); - virtual ~OcTreeBaseSE(); - - /** - * Traces a ray from origin to end (excluding), returning the - * coordinates of all nodes traversed by the beam. - * (Essentially using the DDA algorithm in 3D). - * - * @param origin start coordinate of ray - * @param end end coordinate of ray - * @param ray KeyRay structure that holds the keys of all nodes traversed by the ray, excluding "end" - * @return Success of operation. Returning false usually means that one of the coordinates is out of the OcTree's range - */ - bool computeRayKeys(const point3d& origin, const point3d& end, KeyRay& ray) const; - - NODE* getLUTNeighbor(const point3d& value, OcTreeLUT::NeighborDirection dir) const; - - - protected: - - KeyRay keyray; - OcTreeLUT* lut; - - }; - - -} - -#include "OcTreeBaseSE.hxx" - -#endif diff --git a/octomap/include/octomap/OcTreeBaseSE.hxx b/octomap/include/octomap/OcTreeBaseSE.hxx deleted file mode 100644 index d8adaa76..00000000 --- a/octomap/include/octomap/OcTreeBaseSE.hxx +++ /dev/null @@ -1,192 +0,0 @@ -/* - * OctoMap - An Efficient Probabilistic 3D Mapping Framework Based on Octrees - * http://octomap.github.com/ - * - * Copyright (c) 2009-2013, K.M. Wurm and A. Hornung, University of Freiburg - * All rights reserved. - * License: New BSD - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in the - * documentation and/or other materials provided with the distribution. - * * Neither the name of the University of Freiburg nor the names of its - * contributors may be used to endorse or promote products derived from - * this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - */ - - -#include -#include -#include -#include - -namespace octomap { - - - template - OcTreeBaseSE::OcTreeBaseSE (double _resolution) : - OcTreeBase(_resolution) { - - lut = new OcTreeLUT (this->tree_depth); - } - - template - OcTreeBaseSE::~OcTreeBaseSE () { - delete lut; - } - - - template - bool OcTreeBaseSE::computeRayKeys(const point3d& origin, - const point3d& end, - KeyRay& ray) const { - - // std::cout << "using key ray method\n"; - - // see "A Faster Voxel Traversal Algorithm for Ray Tracing" by Amanatides & Woo - // basically: DDA in 3D - - ray.reset(); - - OcTreeKey key_origin, key_end; - if ( !OcTreeBase::coordToKeyChecked(origin, key_origin) || - !OcTreeBase::coordToKeyChecked(end, key_end) ) { - OCTOMAP_WARNING_STR("Coordinates out of bounds during ray casting"); - return false; - } - - ray.addKey(key_origin); - - if (key_origin == key_end) return true; // same tree cell, we're done. - - - // Initialization phase ------------------------------------------------------- - - point3d direction = (end - origin); - double length = direction.norm2(); - direction /= length; // normalize vector - - int step[3]; - double tMax[3]; - double tDelta[3]; - - OcTreeKey current_key = key_origin; - - for(unsigned int i=0; i < 3; ++i) { - - // compute step direction - if (direction(i) > 0.0) step[i] = 1; - else if (direction(i) < 0.0) step[i] = -1; - else step[i] = 0; - - // compute tMax, tDelta - double voxelBorder = this->keyToCoord(current_key[i]); // negative corner point of voxel - voxelBorder += double(step[i] * this->resolution * 0.5); - - if (step[i] != 0) { - tMax[i] = ( voxelBorder - origin(i) ) / direction(i); - tDelta[i] = this->resolution / fabs( direction(i) ); - } - else { - tMax[i] = std::numeric_limits::max(); - tDelta[i] = std::numeric_limits::max(); - } - } - - // for speedup: - point3d origin_scaled = origin; - origin_scaled /= this->resolution; - double length_scaled = length - this->resolution/2.; // safety margin - length_scaled /= this->resolution; // scale - length_scaled = length_scaled*length_scaled; // avoid sqrt in dist comp. - - // Incremental phase --------------------------------------------------------- - - bool done = false; - while (!done) { - - unsigned int dim; - - // find minimum tMax: - if (tMax[0] < tMax[1]){ - if (tMax[0] < tMax[2]) dim = 0; - else dim = 2; - } - else { - if (tMax[1] < tMax[2]) dim = 1; - else dim = 2; - } - - // advance in direction "dim" - current_key[dim] += step[dim]; - tMax[dim] += tDelta[dim]; - - assert ((current_key[dim] >= 0) && (current_key[dim] < 2*this->tree_max_val)); - - // reached endpoint, key equv? - if (current_key == key_end) { - done = true; - break; - } - else { - - // reached endpoint world coords? - double dist_from_endpoint = 0; - for (unsigned int j = 0; j < 3; j++) { - double coord = (double) current_key[j] - (double) this->tree_max_val; - dist_from_endpoint += (coord - origin_scaled(j)) * (coord - origin_scaled(j)); - } - if (dist_from_endpoint > length_scaled) { - done = true; - break; - } - - else { // continue to add freespace cells - ray.addKey(current_key); - } - } - - assert ( ray.size() < ray.sizeMax() - 1); - - } // end while - - return true; - } - - - - template - NODE* OcTreeBaseSE::getLUTNeighbor (const point3d& node_coord, OcTreeLUT::NeighborDirection dir) const { - - OcTreeKey start_key; - - if (! OcTreeBase::coordToKeyChecked(node_coord, start_key)) { - OCTOMAP_ERROR_STR("Error in search: ["<< node_coord <<"] is out of OcTree bounds!"); - return NULL; - } - - OcTreeKey neighbor_key; - lut->genNeighborKey(start_key, (signed char&) dir, neighbor_key); - return this->search(neighbor_key); - } - - - -} diff --git a/octomap/include/octomap/OcTreeLUT.h b/octomap/include/octomap/OcTreeLUT.h deleted file mode 100644 index bcc30f86..00000000 --- a/octomap/include/octomap/OcTreeLUT.h +++ /dev/null @@ -1,107 +0,0 @@ -/* - * OctoMap - An Efficient Probabilistic 3D Mapping Framework Based on Octrees - * http://octomap.github.com/ - * - * Copyright (c) 2009-2013, K.M. Wurm and A. Hornung, University of Freiburg - * All rights reserved. - * License: New BSD - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in the - * documentation and/or other materials provided with the distribution. - * * Neither the name of the University of Freiburg nor the names of its - * contributors may be used to endorse or promote products derived from - * this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - */ - -#ifndef OCTOMAP_OCTREE_LUT_H -#define OCTOMAP_OCTREE_LUT_H - - -#include "OcTreeLUTdefs.h" -#include "octomap_types.h" -#include "OcTreeKey.h" - -namespace octomap { - - - //! comparator for keys - struct equal_keys { - bool operator() (const unsigned short int* key1, const unsigned short int* key2) const { - return ((key1[0]==key2[0]) && (key1[1] == key2[1]) && (key1[2] == key2[2])); - } - }; - - struct hash_key { - unsigned short int operator()(const unsigned short int* key) const { - return (((31 + key[0]) * 31 + key[1]) * 31 + key[2]); - } - }; - - - - /** - * Implements a lookup table that allows to computer keys of neighbor cells directly, - * see: Samet 1989, "Implementing ray tracing with octrees and neighbor finding" - */ - class OcTreeLUT { - - public: - - /** - * (N)orth: positive X (S)outh: negative X - * (W)est : positive Y (E)ast: negative Y - * (T)op : positive Z (B)ottom: negative Z - */ - - typedef enum { - W = 0, E, N, S , T , B, // face neighbors - SW, NW, SE, NE, TW, BW, TE, BE, TN, TS, BN, BS, // edge neighbors - TNW, TSW, TNE, TSE, BNW, BSW, BNE, BSE // vertex neighbors - } NeighborDirection; - - - public: - - OcTreeLUT(unsigned int _max_depth); - ~OcTreeLUT(); - - bool genNeighborKey(const OcTreeKey& node_key, const signed char& dir, - OcTreeKey& neighbor_key) const; - - protected: - - void initLUT(); - - unsigned int genPos(const OcTreeKey& key, const int& i) const; - void changeKey(const int& val, OcTreeKey& key, const unsigned short int& i) const; - - protected: - - unsigned int max_depth; - - signed char nf_values[8][26]; - signed char nf_rec_values[8][26]; - signed char nf_multiple_values[26][4]; - }; - -} // namespace - -#endif diff --git a/octomap/include/octomap/OcTreeLUTdefs.h b/octomap/include/octomap/OcTreeLUTdefs.h deleted file mode 100644 index 748cb392..00000000 --- a/octomap/include/octomap/OcTreeLUTdefs.h +++ /dev/null @@ -1,157 +0,0 @@ -/* - * OctoMap - An Efficient Probabilistic 3D Mapping Framework Based on Octrees - * http://octomap.github.com/ - * - * Copyright (c) 2009-2013, K.M. Wurm and A. Hornung, University of Freiburg - * All rights reserved. - * License: New BSD - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in the - * documentation and/or other materials provided with the distribution. - * * Neither the name of the University of Freiburg nor the names of its - * contributors may be used to endorse or promote products derived from - * this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - */ - -// TODO: convert defines to ENUMs - -// Lookup table for neighbor search - - //front -#define LUT_N 0 -#define LUT_S 1 -#define LUT_E 2 -#define LUT_W 3 -#define LUT_F 4 -#define LUT_R 5 - - //edge -#define LUT_NW 6 -#define LUT_NE 7 -#define LUT_SW 8 -#define LUT_SE 9 -#define LUT_FN 10 -#define LUT_RN 11 -#define LUT_FS 12 -#define LUT_RS 13 -#define LUT_FE 14 -#define LUT_FW 15 -#define LUT_RE 16 -#define LUT_RW 17 - - //vertex -#define LUT_FNE 18 -#define LUT_FNW 19 -#define LUT_FSE 20 -#define LUT_FSW 21 -#define LUT_RNE 22 -#define LUT_RNW 23 -#define LUT_RSE 24 -#define LUT_RSW 25 - - //edge rec.-values -#define LUT_NW_TO_W 3 -#define LUT_NW_TO_N 6 -#define LUT_NE_TO_E 5 -#define LUT_NE_TO_N 7 -#define LUT_SW_TO_S 7 -#define LUT_SW_TO_W 5 -#define LUT_SE_TO_E 7 -#define LUT_SE_TO_S 8 -#define LUT_FN_TO_F 6 -#define LUT_FN_TO_N 10 -#define LUT_RN_TO_N 11 -#define LUT_RN_TO_R 6 -#define LUT_FS_TO_F 8 -#define LUT_FS_TO_S 11 -#define LUT_RS_TO_R 8 -#define LUT_RS_TO_S 12 -#define LUT_FE_TO_F 10 -#define LUT_FE_TO_E 12 -#define LUT_FW_TO_F 11 -#define LUT_FW_TO_W 12 -#define LUT_RE_TO_R 11 -#define LUT_RE_TO_E 14 -#define LUT_RW_TO_R 12 -#define LUT_RW_TO_W 14 - - //vertex rec.values -#define LUT_FNE_TO_E 16 -#define LUT_FNE_TO_N 18 -#define LUT_FNE_TO_NE 11 -#define LUT_FNE_TO_F 14 -#define LUT_FNE_TO_FN 8 -#define LUT_FNE_TO_FE 4 - -#define LUT_FNW_TO_W 16 -#define LUT_FNW_TO_NW 13 -#define LUT_FNW_TO_N 19 -#define LUT_FNW_TO_FW 4 -#define LUT_FNW_TO_F 15 -#define LUT_FNW_TO_FN 9 - -#define LUT_FSE_TO_S 19 -#define LUT_FSE_TO_SE 11 -#define LUT_FSE_TO_E 18 -#define LUT_FSE_TO_FS 8 -#define LUT_FSE_TO_F 16 -#define LUT_FSE_TO_FE 6 - -#define LUT_FSW_TO_SW 13 -#define LUT_FSW_TO_S 20 -#define LUT_FSW_TO_W 18 -#define LUT_FSW_TO_FS 9 -#define LUT_FSW_TO_FW 6 -#define LUT_FSW_TO_F 17 - -#define LUT_RNE_TO_R 17 -#define LUT_RNE_TO_RE 6 -#define LUT_RNE_TO_RN 11 -#define LUT_RNE_TO_E 20 -#define LUT_RNE_TO_N 22 -#define LUT_RNE_TO_NE 15 - -#define LUT_RNW_TO_RW 6 -#define LUT_RNW_TO_R 18 -#define LUT_RNW_TO_RN 12 -#define LUT_RNW_TO_W 20 -#define LUT_RNW_TO_NW 17 -#define LUT_RNW_TO_N 23 - -#define LUT_RSE_TO_RS 11 -#define LUT_RSE_TO_R 19 -#define LUT_RSE_TO_RE 8 -#define LUT_RSE_TO_S 23 -#define LUT_RSE_TO_SE 15 -#define LUT_RSE_TO_E 22 - -#define LUT_RSW_TO_RS 12 -#define LUT_RSW_TO_RW 8 -#define LUT_RSW_TO_R 20 -#define LUT_RSW_TO_SW 17 -#define LUT_RSW_TO_S 24 -#define LUT_RSW_TO_W 22 - -#define LUT_SELF 0 - -#define LUT_NO_REC 127 - //#define LUT_ 0 - diff --git a/octomap/src/CMakeLists.txt b/octomap/src/CMakeLists.txt index e0fd2eeb..71360504 100644 --- a/octomap/src/CMakeLists.txt +++ b/octomap/src/CMakeLists.txt @@ -7,7 +7,6 @@ SET (octomap_SRCS OcTree.cpp OcTreeNode.cpp OcTreeStamped.cpp - OcTreeLUT.cpp ColorOcTree.cpp ) @@ -60,12 +59,6 @@ TARGET_LINK_LIBRARIES(intersection_example octomap) ADD_EXECUTABLE(octree2pointcloud octree2pointcloud.cpp) TARGET_LINK_LIBRARIES(octree2pointcloud octomap) - -# installation: -# store all header files to install: -# file(GLOB octomap_impl_HDRS *.h *.hxx *.hpp) -# install(FILES ${octomap_impl_HDRS} DESTINATION include/octomap) - install(TARGETS octomap octomap-static diff --git a/octomap/src/OcTreeLUT.cpp b/octomap/src/OcTreeLUT.cpp deleted file mode 100644 index d5571368..00000000 --- a/octomap/src/OcTreeLUT.cpp +++ /dev/null @@ -1,613 +0,0 @@ -/* - * OctoMap - An Efficient Probabilistic 3D Mapping Framework Based on Octrees - * http://octomap.github.com/ - * - * Copyright (c) 2009-2013, R. Schmitt, K.M. Wurm and A. Hornung, - * University of Freiburg. All rights reserved. - * License: New BSD - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in the - * documentation and/or other materials provided with the distribution. - * * Neither the name of the University of Freiburg nor the names of its - * contributors may be used to endorse or promote products derived from - * this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - */ - - -#include -#include -#include - -namespace octomap { - - - OcTreeLUT::OcTreeLUT(unsigned int _max_depth) : - max_depth(_max_depth) { - initLUT(); - } - - OcTreeLUT::~OcTreeLUT() { - } - - void OcTreeLUT::initLUT() { - - // begin Face-Neighbors - // LUT_N - nf_values[0][LUT_S] = nf_values[0][LUT_N] = 2; - nf_values[1][LUT_S] = nf_values[1][LUT_N] = 3; - nf_values[2][LUT_S] = nf_values[2][LUT_N] = 0; - nf_values[3][LUT_S] = nf_values[3][LUT_N] = 1; - nf_values[4][LUT_S] = nf_values[4][LUT_N] = 6; - nf_values[5][LUT_S] = nf_values[5][LUT_N] = 7; - nf_values[6][LUT_S] = nf_values[6][LUT_N] = 4; - nf_values[7][LUT_S] = nf_values[7][LUT_N] = 5; - - nf_rec_values[0][LUT_N] = LUT_NO_REC; - nf_rec_values[1][LUT_N] = LUT_NO_REC; - nf_rec_values[2][LUT_N] = LUT_SELF; - nf_rec_values[3][LUT_N] = LUT_SELF; - nf_rec_values[4][LUT_N] = LUT_NO_REC; - nf_rec_values[5][LUT_N] = LUT_NO_REC; - nf_rec_values[6][LUT_N] = LUT_SELF; - nf_rec_values[7][LUT_N] = LUT_SELF; - - // LUT_S - nf_rec_values[0][LUT_S] = LUT_SELF; - nf_rec_values[1][LUT_S] = LUT_SELF; - nf_rec_values[2][LUT_S] = LUT_NO_REC; - nf_rec_values[3][LUT_S] = LUT_NO_REC; - nf_rec_values[4][LUT_S] = LUT_SELF; - nf_rec_values[5][LUT_S] = LUT_SELF; - nf_rec_values[6][LUT_S] = LUT_NO_REC; - nf_rec_values[7][LUT_S] = LUT_NO_REC; - - // LUT_E - nf_values[0][LUT_W] = nf_values[0][LUT_E] = 1; - nf_values[1][LUT_W] = nf_values[1][LUT_E] = 0; - nf_values[2][LUT_W] = nf_values[2][LUT_E] = 3; - nf_values[3][LUT_W] = nf_values[3][LUT_E] = 2; - nf_values[4][LUT_W] = nf_values[4][LUT_E] = 5; - nf_values[5][LUT_W] = nf_values[5][LUT_E] = 4; - nf_values[6][LUT_W] = nf_values[6][LUT_E] = 7; - nf_values[7][LUT_W] = nf_values[7][LUT_E] = 6; - - nf_rec_values[0][LUT_E] = LUT_NO_REC; - nf_rec_values[1][LUT_E] = LUT_SELF; - nf_rec_values[2][LUT_E] = LUT_NO_REC; - nf_rec_values[3][LUT_E] = LUT_SELF; - nf_rec_values[4][LUT_E] = LUT_NO_REC; - nf_rec_values[5][LUT_E] = LUT_SELF; - nf_rec_values[6][LUT_E] = LUT_NO_REC; - nf_rec_values[7][LUT_E] = LUT_SELF; - - // LUT_W - nf_rec_values[0][LUT_W] = LUT_SELF; - nf_rec_values[1][LUT_W] = LUT_NO_REC; - nf_rec_values[2][LUT_W] = LUT_SELF; - nf_rec_values[3][LUT_W] = LUT_NO_REC; - nf_rec_values[4][LUT_W] = LUT_SELF; - nf_rec_values[5][LUT_W] = LUT_NO_REC; - nf_rec_values[6][LUT_W] = LUT_SELF; - nf_rec_values[7][LUT_W] = LUT_NO_REC; - - // LUT_F - nf_values[0][LUT_R] = nf_values[0][LUT_F] = 4; - nf_values[1][LUT_R] = nf_values[1][LUT_F] = 5; - nf_values[2][LUT_R] = nf_values[2][LUT_F] = 6; - nf_values[3][LUT_R] = nf_values[3][LUT_F] = 7; - nf_values[4][LUT_R] = nf_values[4][LUT_F] = 0; - nf_values[5][LUT_R] = nf_values[5][LUT_F] = 1; - nf_values[6][LUT_R] = nf_values[6][LUT_F] = 2; - nf_values[7][LUT_R] = nf_values[7][LUT_F] = 3; - - nf_rec_values[0][LUT_F] = LUT_NO_REC; - nf_rec_values[1][LUT_F] = LUT_NO_REC; - nf_rec_values[2][LUT_F] = LUT_NO_REC; - nf_rec_values[3][LUT_F] = LUT_NO_REC; - nf_rec_values[4][LUT_F] = LUT_SELF; - nf_rec_values[5][LUT_F] = LUT_SELF; - nf_rec_values[6][LUT_F] = LUT_SELF; - nf_rec_values[7][LUT_F] = LUT_SELF; - - // LUT_R - nf_rec_values[0][LUT_R] = LUT_SELF; - nf_rec_values[1][LUT_R] = LUT_SELF; - nf_rec_values[2][LUT_R] = LUT_SELF; - nf_rec_values[3][LUT_R] = LUT_SELF; - nf_rec_values[4][LUT_R] = LUT_NO_REC; - nf_rec_values[5][LUT_R] = LUT_NO_REC; - nf_rec_values[6][LUT_R] = LUT_NO_REC; - nf_rec_values[7][LUT_R] = LUT_NO_REC; - // end Face-Neighbors - - - // begin Edge-Neighbors - // LUT_NW - for (int i = LUT_NW; i < LUT_SE+1; ++i) { - nf_values[0][i] = 3; - nf_values[1][i] = 2; - nf_values[2][i] = 1; - nf_values[3][i] = 0; - nf_values[4][i] = 7; - nf_values[5][i] = 6; - nf_values[6][i] = 5; - nf_values[7][i] = 4; - } - - nf_rec_values[0][LUT_NW] = LUT_NW_TO_W; - nf_rec_values[1][LUT_NW] = LUT_NO_REC; - nf_rec_values[2][LUT_NW] = LUT_SELF; - nf_rec_values[3][LUT_NW] = LUT_NW_TO_N; - nf_rec_values[4][LUT_NW] = LUT_NW_TO_W; - nf_rec_values[5][LUT_NW] = LUT_NO_REC; - nf_rec_values[6][LUT_NW] = LUT_SELF; - nf_rec_values[7][LUT_NW] = LUT_NW_TO_N; - - // LUT_NE - nf_rec_values[0][LUT_NE] = LUT_NO_REC; - nf_rec_values[1][LUT_NE] = LUT_NE_TO_E; - nf_rec_values[2][LUT_NE] = LUT_NE_TO_N; - nf_rec_values[3][LUT_NE] = LUT_SELF; - nf_rec_values[4][LUT_NE] = LUT_NO_REC; - nf_rec_values[5][LUT_NE] = LUT_NE_TO_E; - nf_rec_values[6][LUT_NE] = LUT_NE_TO_N; - nf_rec_values[7][LUT_NE] = LUT_SELF; - - // LUT_SW - nf_rec_values[0][LUT_SW] = LUT_SELF; - nf_rec_values[1][LUT_SW] = LUT_SW_TO_S; - nf_rec_values[2][LUT_SW] = LUT_SW_TO_W; - nf_rec_values[3][LUT_SW] = LUT_NO_REC; - nf_rec_values[4][LUT_SW] = LUT_SELF; - nf_rec_values[5][LUT_SW] = LUT_SW_TO_S; - nf_rec_values[6][LUT_SW] = LUT_SW_TO_W; - nf_rec_values[7][LUT_SW] = LUT_NO_REC; - - // LUT_SE - nf_rec_values[0][LUT_SE] = LUT_SE_TO_S; - nf_rec_values[1][LUT_SE] = LUT_SELF; - nf_rec_values[2][LUT_SE] = LUT_NO_REC; - nf_rec_values[3][LUT_SE] = LUT_SE_TO_E; - nf_rec_values[4][LUT_SE] = LUT_SE_TO_S; - nf_rec_values[5][LUT_SE] = LUT_SELF; - nf_rec_values[6][LUT_SE] = LUT_NO_REC; - nf_rec_values[7][LUT_SE] = LUT_SE_TO_E; - - // LUT_FN - for (int i = LUT_FN; i < LUT_RS+1; ++i) { - nf_values[0][i] = 6; - nf_values[1][i] = 7; - nf_values[2][i] = 4; - nf_values[3][i] = 5; - nf_values[4][i] = 2; - nf_values[5][i] = 3; - nf_values[6][i] = 0; - nf_values[7][i] = 1; - } - - nf_rec_values[0][LUT_FN] = LUT_NO_REC; - nf_rec_values[1][LUT_FN] = LUT_NO_REC; - nf_rec_values[2][LUT_FN] = LUT_FN_TO_N; - nf_rec_values[3][LUT_FN] = LUT_FN_TO_N; - nf_rec_values[4][LUT_FN] = LUT_FN_TO_F; - nf_rec_values[5][LUT_FN] = LUT_FN_TO_F; - nf_rec_values[6][LUT_FN] = LUT_SELF; - nf_rec_values[7][LUT_FN] = LUT_SELF; - - // LUT_RN - nf_rec_values[0][LUT_RN] = LUT_RN_TO_R; - nf_rec_values[1][LUT_RN] = LUT_RN_TO_R; - nf_rec_values[2][LUT_RN] = LUT_SELF; - nf_rec_values[3][LUT_RN] = LUT_SELF; - nf_rec_values[4][LUT_RN] = LUT_NO_REC; - nf_rec_values[5][LUT_RN] = LUT_NO_REC; - nf_rec_values[6][LUT_RN] = LUT_RN_TO_N; - nf_rec_values[7][LUT_RN] = LUT_RN_TO_N; - - // LUT_FS - nf_rec_values[0][LUT_FS] = LUT_FS_TO_S; - nf_rec_values[1][LUT_FS] = LUT_FS_TO_S; - nf_rec_values[2][LUT_FS] = LUT_NO_REC; - nf_rec_values[3][LUT_FS] = LUT_NO_REC; - nf_rec_values[4][LUT_FS] = LUT_SELF; - nf_rec_values[5][LUT_FS] = LUT_SELF; - nf_rec_values[6][LUT_FS] = LUT_FS_TO_F; - nf_rec_values[7][LUT_FS] = LUT_FS_TO_F; - - // LUT_RS - nf_rec_values[0][LUT_RS] = LUT_SELF; - nf_rec_values[1][LUT_RS] = LUT_SELF; - nf_rec_values[2][LUT_RS] = LUT_RS_TO_R; - nf_rec_values[3][LUT_RS] = LUT_RS_TO_R; - nf_rec_values[4][LUT_RS] = LUT_RS_TO_S; - nf_rec_values[5][LUT_RS] = LUT_RS_TO_S; - nf_rec_values[6][LUT_RS] = LUT_NO_REC; - nf_rec_values[7][LUT_RS] = LUT_NO_REC; - - // LUT_FE - for (int i = LUT_FE; i < LUT_RW+1; ++i) { - nf_values[0][i] = 5; - nf_values[1][i] = 4; - nf_values[2][i] = 7; - nf_values[3][i] = 6; - nf_values[4][i] = 1; - nf_values[5][i] = 0; - nf_values[6][i] = 3; - nf_values[7][i] = 2; - } - - nf_rec_values[0][LUT_FE] = LUT_NO_REC; - nf_rec_values[1][LUT_FE] = LUT_FE_TO_E; - nf_rec_values[2][LUT_FE] = LUT_NO_REC; - nf_rec_values[3][LUT_FE] = LUT_FE_TO_E; - nf_rec_values[4][LUT_FE] = LUT_FE_TO_F; - nf_rec_values[5][LUT_FE] = LUT_SELF; - nf_rec_values[6][LUT_FE] = LUT_FE_TO_F; - nf_rec_values[7][LUT_FE] = LUT_SELF; - - // LUT_FW - nf_rec_values[0][LUT_FW] = LUT_FW_TO_W; - nf_rec_values[1][LUT_FW] = LUT_NO_REC; - nf_rec_values[2][LUT_FW] = LUT_FW_TO_W; - nf_rec_values[3][LUT_FW] = LUT_NO_REC; - nf_rec_values[4][LUT_FW] = LUT_SELF; - nf_rec_values[5][LUT_FW] = LUT_FW_TO_F; - nf_rec_values[6][LUT_FW] = LUT_SELF; - nf_rec_values[7][LUT_FW] = LUT_FW_TO_F; - - // LUT_RE - nf_rec_values[0][LUT_RE] = LUT_RE_TO_R; - nf_rec_values[1][LUT_RE] = LUT_SELF; - nf_rec_values[2][LUT_RE] = LUT_RE_TO_R; - nf_rec_values[3][LUT_RE] = LUT_SELF; - nf_rec_values[4][LUT_RE] = LUT_NO_REC; - nf_rec_values[5][LUT_RE] = LUT_RE_TO_E; - nf_rec_values[6][LUT_RE] = LUT_NO_REC; - nf_rec_values[7][LUT_RE] = LUT_RE_TO_E; - - // LUT_RW - nf_rec_values[0][LUT_RW] = LUT_SELF; - nf_rec_values[1][LUT_RW] = LUT_RW_TO_R; - nf_rec_values[2][LUT_RW] = LUT_SELF; - nf_rec_values[3][LUT_RW] = LUT_RW_TO_R; - nf_rec_values[4][LUT_RW] = LUT_RW_TO_W; - nf_rec_values[5][LUT_RW] = LUT_NO_REC; - nf_rec_values[6][LUT_RW] = LUT_RW_TO_W; - nf_rec_values[7][LUT_RW] = LUT_NO_REC; - - // end Edge-Neighbors - - - // begin Vertex-Neighbors - // LUT_FNE - for (int i = LUT_FNE; i < LUT_RSW+1; ++i) { - nf_values[0][i] = 7; - nf_values[1][i] = 6; - nf_values[2][i] = 5; - nf_values[3][i] = 4; - nf_values[4][i] = 3; - nf_values[5][i] = 2; - nf_values[6][i] = 1; - nf_values[7][i] = 0; - } - - nf_rec_values[0][LUT_FNE] = LUT_NO_REC; - nf_rec_values[1][LUT_FNE] = LUT_FNE_TO_E; - nf_rec_values[2][LUT_FNE] = LUT_FNE_TO_N; - nf_rec_values[3][LUT_FNE] = LUT_FNE_TO_NE; - nf_rec_values[4][LUT_FNE] = LUT_FNE_TO_F; - nf_rec_values[5][LUT_FNE] = LUT_FNE_TO_FE; - nf_rec_values[6][LUT_FNE] = LUT_FNE_TO_FN; - nf_rec_values[7][LUT_FNE] = LUT_SELF; - - // LUT_FNW - nf_rec_values[0][LUT_FNW] = LUT_FNW_TO_W; - nf_rec_values[1][LUT_FNW] = LUT_NO_REC; - nf_rec_values[2][LUT_FNW] = LUT_FNW_TO_NW; - nf_rec_values[3][LUT_FNW] = LUT_FNW_TO_N; - nf_rec_values[4][LUT_FNW] = LUT_FNW_TO_FW; - nf_rec_values[5][LUT_FNW] = LUT_FNW_TO_F; - nf_rec_values[6][LUT_FNW] = LUT_SELF; - nf_rec_values[7][LUT_FNW] = LUT_FNW_TO_FN; - - // LUT_FSE - nf_rec_values[0][LUT_FSE] = LUT_FSE_TO_S; - nf_rec_values[1][LUT_FSE] = LUT_FSE_TO_SE; - nf_rec_values[2][LUT_FSE] = LUT_NO_REC; - nf_rec_values[3][LUT_FSE] = LUT_FSE_TO_E; - nf_rec_values[4][LUT_FSE] = LUT_FSE_TO_FS; - nf_rec_values[5][LUT_FSE] = LUT_SELF; - nf_rec_values[6][LUT_FSE] = LUT_FSE_TO_F; - nf_rec_values[7][LUT_FSE] = LUT_FSE_TO_FE; - - // LUT_FSW - nf_rec_values[0][LUT_FSW] = LUT_FSW_TO_SW; - nf_rec_values[1][LUT_FSW] = LUT_FSW_TO_S; - nf_rec_values[2][LUT_FSW] = LUT_FSW_TO_W; - nf_rec_values[3][LUT_FSW] = LUT_NO_REC; - nf_rec_values[4][LUT_FSW] = LUT_SELF; - nf_rec_values[5][LUT_FSW] = LUT_FSW_TO_FS; - nf_rec_values[6][LUT_FSW] = LUT_FSW_TO_FW; - nf_rec_values[7][LUT_FSW] = LUT_FSW_TO_F; - - // LUT_RNE - nf_rec_values[0][LUT_RNE] = LUT_RNE_TO_R; - nf_rec_values[1][LUT_RNE] = LUT_RNE_TO_RE; - nf_rec_values[2][LUT_RNE] = LUT_RNE_TO_RN; - nf_rec_values[3][LUT_RNE] = LUT_SELF; - nf_rec_values[4][LUT_RNE] = LUT_NO_REC; - nf_rec_values[5][LUT_RNE] = LUT_RNE_TO_E; - nf_rec_values[6][LUT_RNE] = LUT_RNE_TO_N; - nf_rec_values[7][LUT_RNE] = LUT_RNE_TO_NE; - - // LUT_RNW - nf_rec_values[0][LUT_RNW] = LUT_RNW_TO_RW; - nf_rec_values[1][LUT_RNW] = LUT_RNW_TO_R; - nf_rec_values[2][LUT_RNW] = LUT_SELF; - nf_rec_values[3][LUT_RNW] = LUT_RNW_TO_RN; - nf_rec_values[4][LUT_RNW] = LUT_RNW_TO_W; - nf_rec_values[5][LUT_RNW] = LUT_NO_REC; - nf_rec_values[6][LUT_RNW] = LUT_RNW_TO_NW; - nf_rec_values[7][LUT_RNW] = LUT_RNW_TO_N; - - // LUT_RSE - nf_rec_values[0][LUT_RSE] = LUT_RSE_TO_RS; - nf_rec_values[1][LUT_RSE] = LUT_SELF; - nf_rec_values[2][LUT_RSE] = LUT_RSE_TO_R; - nf_rec_values[3][LUT_RSE] = LUT_RSE_TO_RE; - nf_rec_values[4][LUT_RSE] = LUT_RSE_TO_S; - nf_rec_values[5][LUT_RSE] = LUT_RSE_TO_SE; - nf_rec_values[6][LUT_RSE] = LUT_NO_REC; - nf_rec_values[7][LUT_RSE] = LUT_RSE_TO_E; - - // LUT_RSW - nf_rec_values[0][LUT_RSW] = LUT_SELF; - nf_rec_values[1][LUT_RSW] = LUT_RSW_TO_RS; - nf_rec_values[2][LUT_RSW] = LUT_RSW_TO_RW; - nf_rec_values[3][LUT_RSW] = LUT_RSW_TO_R; - nf_rec_values[4][LUT_RSW] = LUT_RSW_TO_SW; - nf_rec_values[5][LUT_RSW] = LUT_RSW_TO_S; - nf_rec_values[6][LUT_RSW] = LUT_RSW_TO_W; - nf_rec_values[7][LUT_RSW] = LUT_NO_REC; - - - nf_multiple_values[LUT_N][0] = 0; - nf_multiple_values[LUT_N][1] = 1; - nf_multiple_values[LUT_N][2] = 4; - nf_multiple_values[LUT_N][3] = 5; - - nf_multiple_values[LUT_S][0] = 2; - nf_multiple_values[LUT_S][1] = 3; - nf_multiple_values[LUT_S][2] = 6; - nf_multiple_values[LUT_S][3] = 7; - - nf_multiple_values[LUT_E][0] = 0; - nf_multiple_values[LUT_E][1] = 2; - nf_multiple_values[LUT_E][2] = 4; - nf_multiple_values[LUT_E][3] = 6; - - nf_multiple_values[LUT_W][0] = 1; - nf_multiple_values[LUT_W][1] = 3; - nf_multiple_values[LUT_W][2] = 5; - nf_multiple_values[LUT_W][3] = 7; - - nf_multiple_values[LUT_F][0] = 0; - nf_multiple_values[LUT_F][1] = 1; - nf_multiple_values[LUT_F][2] = 2; - nf_multiple_values[LUT_F][3] = 3; - - nf_multiple_values[LUT_R][0] = 4; - nf_multiple_values[LUT_R][1] = 5; - nf_multiple_values[LUT_R][2] = 6; - nf_multiple_values[LUT_R][3] = 7; - - nf_multiple_values[LUT_NW][0] = 1; - nf_multiple_values[LUT_NW][1] = 5; - nf_multiple_values[LUT_NW][2] = LUT_NO_REC; - nf_multiple_values[LUT_NW][3] = LUT_NO_REC; - - nf_multiple_values[LUT_NE][0] = 0; - nf_multiple_values[LUT_NE][1] = 4; - nf_multiple_values[LUT_NE][2] = LUT_NO_REC; - nf_multiple_values[LUT_NE][3] = LUT_NO_REC; - - nf_multiple_values[LUT_SW][0] = 3; - nf_multiple_values[LUT_SW][1] = 7; - nf_multiple_values[LUT_SW][2] = LUT_NO_REC; - nf_multiple_values[LUT_SW][3] = LUT_NO_REC; - - nf_multiple_values[LUT_SE][0] = 2; - nf_multiple_values[LUT_SE][1] = 6; - nf_multiple_values[LUT_SE][2] = LUT_NO_REC; - nf_multiple_values[LUT_SE][3] = LUT_NO_REC; - - nf_multiple_values[LUT_FN][0] = 1; - nf_multiple_values[LUT_FN][1] = 3; - nf_multiple_values[LUT_FN][2] = LUT_NO_REC; - nf_multiple_values[LUT_FN][3] = LUT_NO_REC; - - nf_multiple_values[LUT_RN][0] = 4; - nf_multiple_values[LUT_RN][1] = 5; - nf_multiple_values[LUT_RN][2] = LUT_NO_REC; - nf_multiple_values[LUT_RN][3] = LUT_NO_REC; - - nf_multiple_values[LUT_FS][0] = 2; - nf_multiple_values[LUT_FS][1] = 3; - nf_multiple_values[LUT_FS][2] = LUT_NO_REC; - nf_multiple_values[LUT_FS][3] = LUT_NO_REC; - - nf_multiple_values[LUT_RS][0] = 6; - nf_multiple_values[LUT_RS][1] = 7; - nf_multiple_values[LUT_RS][2] = LUT_NO_REC; - nf_multiple_values[LUT_RS][3] = LUT_NO_REC; - - nf_multiple_values[LUT_FE][0] = 0; - nf_multiple_values[LUT_FE][1] = 2; - nf_multiple_values[LUT_FE][2] = LUT_NO_REC; - nf_multiple_values[LUT_FE][3] = LUT_NO_REC; - - nf_multiple_values[LUT_FW][0] = 1; - nf_multiple_values[LUT_FW][1] = 3; - nf_multiple_values[LUT_FW][2] = LUT_NO_REC; - nf_multiple_values[LUT_FW][3] = LUT_NO_REC; - - nf_multiple_values[LUT_RE][0] = 4; - nf_multiple_values[LUT_RE][1] = 6; - nf_multiple_values[LUT_RE][2] = LUT_NO_REC; - nf_multiple_values[LUT_RE][3] = LUT_NO_REC; - - nf_multiple_values[LUT_RW][0] = 5; - nf_multiple_values[LUT_RW][1] = 7; - nf_multiple_values[LUT_RW][2] = LUT_NO_REC; - nf_multiple_values[LUT_RW][3] = LUT_NO_REC; - - nf_multiple_values[LUT_FNE][0] = 0; - nf_multiple_values[LUT_FNE][1] = LUT_NO_REC; - nf_multiple_values[LUT_FNE][2] = LUT_NO_REC; - nf_multiple_values[LUT_FNE][3] = LUT_NO_REC; - - nf_multiple_values[LUT_FNW][0] = 1; - nf_multiple_values[LUT_FNW][1] = LUT_NO_REC; - nf_multiple_values[LUT_FNW][2] = LUT_NO_REC; - nf_multiple_values[LUT_FNW][3] = LUT_NO_REC; - - nf_multiple_values[LUT_FSE][0] = 2; - nf_multiple_values[LUT_FSE][1] = LUT_NO_REC; - nf_multiple_values[LUT_FSE][2] = LUT_NO_REC; - nf_multiple_values[LUT_FSE][3] = LUT_NO_REC; - - nf_multiple_values[LUT_FSW][0] = 3; - nf_multiple_values[LUT_FSW][1] = LUT_NO_REC; - nf_multiple_values[LUT_FSW][2] = LUT_NO_REC; - nf_multiple_values[LUT_FSW][3] = LUT_NO_REC; - - nf_multiple_values[LUT_RNE][0] = 4; - nf_multiple_values[LUT_RNE][1] = LUT_NO_REC; - nf_multiple_values[LUT_RNE][2] = LUT_NO_REC; - nf_multiple_values[LUT_RNE][3] = LUT_NO_REC; - - nf_multiple_values[LUT_RNW][0] = 5; - nf_multiple_values[LUT_RNW][1] = LUT_NO_REC; - nf_multiple_values[LUT_RNW][2] = LUT_NO_REC; - nf_multiple_values[LUT_RNW][3] = LUT_NO_REC; - - nf_multiple_values[LUT_RSE][0] = 6; - nf_multiple_values[LUT_RSE][1] = LUT_NO_REC; - nf_multiple_values[LUT_RSE][2] = LUT_NO_REC; - nf_multiple_values[LUT_RSE][3] = LUT_NO_REC; - - nf_multiple_values[LUT_RSW][0] = 7; - nf_multiple_values[LUT_RSW][1] = LUT_NO_REC; - nf_multiple_values[LUT_RSW][2] = LUT_NO_REC; - nf_multiple_values[LUT_RSW][3] = LUT_NO_REC; - - }; - - - unsigned int OcTreeLUT::genPos(const OcTreeKey& key, const int& i) const { - unsigned int retval = 0; - if (key.k[0] & (1 << i)) retval += 1; - if (key.k[1] & (1 << i)) retval += 2; - if (key.k[2] & (1 << i)) retval += 4; - return retval; - } - - - /* - * used internally to generate neighbor key from a given key - */ - void OcTreeLUT::changeKey(const int& val, OcTreeKey& key, const unsigned short int& i) const { - switch (val) { - case 0: - key.k[0] &= ~(1 << i); - key.k[1] &= ~(1 << i); - key.k[2] &= ~(1 << i); - break; - case 1: - key.k[0] |= (1 << i); - key.k[1] &= ~(1 << i); - key.k[2] &= ~(1 << i); - break; - case 2: - key.k[0] &= ~(1 << i); - key.k[1] |= (1 << i); - key.k[2] &= ~(1 << i); - break; - case 3: - key.k[0] |= (1 << i); - key.k[1] |= (1 << i); - key.k[2] &= ~(1 << i); - break; - case 4: - key.k[0] &= ~(1 << i); - key.k[1] &= ~(1 << i); - key.k[2] |= (1 << i); - break; - case 5: - key.k[0] |= (1 << i); - key.k[1] &= ~(1 << i); - key.k[2] |= (1 << i); - break; - case 6: - key.k[0] &= ~(1 << i); - key.k[1] |= (1 << i); - key.k[2] |= (1 << i); - break; - case 7: - key.k[0] |= (1 << i); - key.k[1] |= (1 << i); - key.k[2] |= (1 << i); - break; - } - } - - - bool OcTreeLUT::genNeighborKey(const OcTreeKey& node_key, const signed char& dir, - OcTreeKey& neighbor_key) const { - - neighbor_key.k[0] = node_key.k[0]; - neighbor_key.k[1] = node_key.k[1]; - neighbor_key.k[2] = node_key.k[2]; - - unsigned int depth = 0; - signed char curDir = dir; - - signed char pos; - while (depth < max_depth) { - pos = static_cast(genPos(neighbor_key, depth)); - changeKey(nf_values[pos][curDir], neighbor_key, depth); - - if (nf_rec_values[pos][curDir] != LUT_NO_REC) { // recurs - curDir -= nf_rec_values[pos][curDir]; - depth++; - } - else { - return true; - } - } - - return false; - }; - - - -} // namespace - diff --git a/octomap/src/testing/CMakeLists.txt b/octomap/src/testing/CMakeLists.txt index 19f6d4d0..75e3de10 100644 --- a/octomap/src/testing/CMakeLists.txt +++ b/octomap/src/testing/CMakeLists.txt @@ -14,9 +14,6 @@ TARGET_LINK_LIBRARIES(test_changedkeys octomap) ADD_EXECUTABLE(test_scans test_scans.cpp) TARGET_LINK_LIBRARIES(test_scans octomap) -ADD_EXECUTABLE(test_lut test_lut.cpp) -TARGET_LINK_LIBRARIES(test_lut octomap) - ADD_EXECUTABLE(test_color_tree test_color_tree.cpp) TARGET_LINK_LIBRARIES(test_color_tree octomap) diff --git a/octomap/src/testing/test_lut.cpp b/octomap/src/testing/test_lut.cpp deleted file mode 100644 index 684d4a17..00000000 --- a/octomap/src/testing/test_lut.cpp +++ /dev/null @@ -1,67 +0,0 @@ - -#include -#include -#include - -using namespace std; -using namespace octomap; -using namespace octomath; - - - -int main(int argc, char** argv) { - - OcTreeLUT lut(16); - - // OcTreeKey start_key (32768, 32768, 32768); - OcTreeKey start_key (100, 100, 100); - OcTreeKey neighbor_key; - - cout << endl << "center key:" << endl; - cout << "[" << start_key.k[0] << "," << start_key.k[1] << "," << start_key.k[2] << "]" << endl; - - cout << endl << "face neighbor keys:" << endl; - - lut.genNeighborKey(start_key, OcTreeLUT::N, neighbor_key); - cout << "N -> [" << neighbor_key.k[0] << "," << neighbor_key.k[1] << "," << neighbor_key.k[2] << "]" << endl; - - lut.genNeighborKey(start_key, OcTreeLUT::S, neighbor_key); - cout << "S -> [" << neighbor_key.k[0] << "," << neighbor_key.k[1] << "," << neighbor_key.k[2] << "]" << endl; - - lut.genNeighborKey(start_key, OcTreeLUT::W, neighbor_key); - cout << "W -> [" << neighbor_key.k[0] << "," << neighbor_key.k[1] << "," << neighbor_key.k[2] << "]" << endl; - - lut.genNeighborKey(start_key, OcTreeLUT::E, neighbor_key); - cout << "E -> [" << neighbor_key.k[0] << "," << neighbor_key.k[1] << "," << neighbor_key.k[2] << "]" << endl; - - lut.genNeighborKey(start_key, OcTreeLUT::T, neighbor_key); - cout << "T -> [" << neighbor_key.k[0] << "," << neighbor_key.k[1] << "," << neighbor_key.k[2] << "]" << endl; - - lut.genNeighborKey(start_key, OcTreeLUT::B, neighbor_key); - cout << "B -> [" << neighbor_key.k[0] << "," << neighbor_key.k[1] << "," << neighbor_key.k[2] << "]" << endl; - - cout << endl << "some edge neighbor keys:" << endl; - - lut.genNeighborKey(start_key, OcTreeLUT::SE, neighbor_key); - cout << "SE -> [" << neighbor_key.k[0] << "," << neighbor_key.k[1] << "," << neighbor_key.k[2] << "]" << endl; - - lut.genNeighborKey(start_key, OcTreeLUT::SW, neighbor_key); - cout << "SW -> [" << neighbor_key.k[0] << "," << neighbor_key.k[1] << "," << neighbor_key.k[2] << "]" << endl; - - lut.genNeighborKey(start_key, OcTreeLUT::BS, neighbor_key); - cout << "BS -> [" << neighbor_key.k[0] << "," << neighbor_key.k[1] << "," << neighbor_key.k[2] << "]" << endl; - - cout << endl << "some vertex neighbor keys:" << endl; - - lut.genNeighborKey(start_key, OcTreeLUT::TNW, neighbor_key); - cout << "TNW -> [" << neighbor_key.k[0] << "," << neighbor_key.k[1] << "," << neighbor_key.k[2] << "]" << endl; - - lut.genNeighborKey(start_key, OcTreeLUT::BNW, neighbor_key); - cout << "BNW -> [" << neighbor_key.k[0] << "," << neighbor_key.k[1] << "," << neighbor_key.k[2] << "]" << endl; - - lut.genNeighborKey(start_key, OcTreeLUT::BSE, neighbor_key); - cout << "BSE -> [" << neighbor_key.k[0] << "," << neighbor_key.k[1] << "," << neighbor_key.k[2] << "]" << endl; - - - return 0; -} From 94bf7a0c1956b94ecbee0e0047f970d86159ddaf Mon Sep 17 00:00:00 2001 From: Armin Hornung Date: Sun, 17 Apr 2016 17:34:30 +0200 Subject: [PATCH 25/28] Cleanup: remove no longer used ROS logging macros --- octomap/include/octomap/octomap_types.h | 44 +++++++++---------------- 1 file changed, 15 insertions(+), 29 deletions(-) diff --git a/octomap/include/octomap/octomap_types.h b/octomap/include/octomap/octomap_types.h index 8fb54d34..328a0b7c 100644 --- a/octomap/include/octomap/octomap_types.h +++ b/octomap/include/octomap/octomap_types.h @@ -57,38 +57,24 @@ namespace octomap { } - //Macros for compiling with an without ROS (for output logging) - #ifdef OCTOMAP_ROS - #include - - #define OCTOMAP_DEBUG ROS_DEBUG - #define OCTOMAP_DEBUG_STR ROS_DEBUG_STREAM - #define OCTOMAP_WARNING ROS_WARN - #define OCTOMAP_WARNING_STR ROS_WARN_STREAM - #define OCTOMAP_ERROR ROS_ERROR - #define OCTOMAP_ERROR_STR ROS_ERROR_STREAM - - #else - // no debug output if not in debug mode: - #ifdef NDEBUG - #ifndef OCTOMAP_NODEBUGOUT - #define OCTOMAP_NODEBUGOUT - #endif - #endif - - #ifdef OCTOMAP_NODEBUGOUT - #define OCTOMAP_DEBUG(...) (void)0 - #define OCTOMAP_DEBUG_STR(...) (void)0 - #else - #define OCTOMAP_DEBUG(...) fprintf(stderr, __VA_ARGS__), fflush(stderr) - #define OCTOMAP_DEBUG_STR(args) std::cerr << args << std::endl + // no debug output if not in debug mode: + #ifdef NDEBUG + #ifndef OCTOMAP_NODEBUGOUT + #define OCTOMAP_NODEBUGOUT #endif + #endif - #define OCTOMAP_WARNING(...) fprintf(stderr, "WARNING: "), fprintf(stderr, __VA_ARGS__), fflush(stderr) - #define OCTOMAP_WARNING_STR(args) std::cerr << "WARNING: " << args << std::endl - #define OCTOMAP_ERROR(...) fprintf(stderr, "ERROR: "), fprintf(stderr, __VA_ARGS__), fflush(stderr) - #define OCTOMAP_ERROR_STR(args) std::cerr << "ERROR: " << args << std::endl + #ifdef OCTOMAP_NODEBUGOUT + #define OCTOMAP_DEBUG(...) (void)0 + #define OCTOMAP_DEBUG_STR(...) (void)0 + #else + #define OCTOMAP_DEBUG(...) fprintf(stderr, __VA_ARGS__), fflush(stderr) + #define OCTOMAP_DEBUG_STR(args) std::cerr << args << std::endl #endif + #define OCTOMAP_WARNING(...) fprintf(stderr, "WARNING: "), fprintf(stderr, __VA_ARGS__), fflush(stderr) + #define OCTOMAP_WARNING_STR(args) std::cerr << "WARNING: " << args << std::endl + #define OCTOMAP_ERROR(...) fprintf(stderr, "ERROR: "), fprintf(stderr, __VA_ARGS__), fflush(stderr) + #define OCTOMAP_ERROR_STR(args) std::cerr << "ERROR: " << args << std::endl #endif From 50bacb1479f96d395af25d35e3a31323389abb6d Mon Sep 17 00:00:00 2001 From: Armin Hornung Date: Sun, 17 Apr 2016 17:39:22 +0200 Subject: [PATCH 26/28] Cleanup: remove deprecated insertScan functions (replaced by insertPointCloud long ago) --- octomap/include/octomap/OccupancyOcTreeBase.h | 24 ------------------- 1 file changed, 24 deletions(-) diff --git a/octomap/include/octomap/OccupancyOcTreeBase.h b/octomap/include/octomap/OccupancyOcTreeBase.h index 048fcee2..a8532143 100644 --- a/octomap/include/octomap/OccupancyOcTreeBase.h +++ b/octomap/include/octomap/OccupancyOcTreeBase.h @@ -131,30 +131,6 @@ namespace octomap { */ virtual void insertPointCloud(const ScanNode& scan, double maxrange=-1., bool lazy_eval = false, bool discretize = false); - /// @note Deprecated, use insertPointCloud() instead. pruning is now done automatically. - OCTOMAP_DEPRECATED(virtual void insertScan(const Pointcloud& scan, const octomap::point3d& sensor_origin, - double maxrange=-1., bool pruning=true, bool lazy_eval = false)) - { - this->insertPointCloud(scan, sensor_origin, maxrange, lazy_eval); - } - - /// @note Deprecated, use insertPointCloud() instead. pruning is now done automatically. - OCTOMAP_DEPRECATED(virtual void insertScan(const Pointcloud& scan, const point3d& sensor_origin, - const pose6d& frame_origin, double maxrange=-1., bool pruning = true, bool lazy_eval = false)) - { - this->insertPointCloud(scan, sensor_origin, frame_origin, maxrange, lazy_eval); - } - - /// @note Deprecated, use insertPointCloud() instead. pruning is now done automatically. - OCTOMAP_DEPRECATED(virtual void insertScan(const ScanNode& scan, double maxrange=-1., bool pruning = true, bool lazy_eval = false)){ - this->insertPointCloud(scan, maxrange, lazy_eval); - } - - /// @note Deprecated, use insertPointCloudRays instead. pruning is now done automatically. - OCTOMAP_DEPRECATED( virtual void insertScanNaive(const Pointcloud& scan, const point3d& sensor_origin, double maxrange, bool lazy_eval = false)){ - this->insertPointCloudRays(scan, sensor_origin, maxrange, lazy_eval); - } - /** * Integrate a Pointcloud (in global reference frame), parallelized with OpenMP. * This function simply inserts all rays of the point clouds as batch operation. From e8af5a8d4fea8260ad0b725279fd8b6ba92b3f4a Mon Sep 17 00:00:00 2001 From: Armin Hornung Date: Sun, 17 Apr 2016 21:48:44 +0200 Subject: [PATCH 27/28] Internal version of libQGLViewer updated to 2.6.3 --- octovis/src/extern/QGLViewer/CHANGELOG | 2 +- octovis/src/extern/QGLViewer/INSTALL | 8 +- .../extern/QGLViewer/ImageInterface.Qt3.ui | 276 -- octovis/src/extern/QGLViewer/LICENCE | 2 +- octovis/src/extern/QGLViewer/QGLViewer.pro | 373 +- octovis/src/extern/QGLViewer/README | 4 +- .../extern/QGLViewer/VRender/AxisAlignedBox.h | 4 +- .../QGLViewer/VRender/BSPSortMethod.cpp | 4 +- .../VRender/BackFaceCullingOptimizer.cpp | 10 +- .../extern/QGLViewer/VRender/EPSExporter.cpp | 4 +- .../src/extern/QGLViewer/VRender/Exporter.cpp | 19 +- .../src/extern/QGLViewer/VRender/Exporter.h | 13 +- .../extern/QGLViewer/VRender/FIGExporter.cpp | 4 +- .../src/extern/QGLViewer/VRender/NVector3.cpp | 4 +- .../src/extern/QGLViewer/VRender/NVector3.h | 4 +- .../src/extern/QGLViewer/VRender/Optimizer.h | 4 +- .../src/extern/QGLViewer/VRender/ParserGL.cpp | 12 +- .../src/extern/QGLViewer/VRender/ParserGL.h | 4 +- .../extern/QGLViewer/VRender/Primitive.cpp | 21 +- .../src/extern/QGLViewer/VRender/Primitive.h | 247 +- .../VRender/PrimitivePositioning.cpp | 94 +- .../QGLViewer/VRender/PrimitivePositioning.h | 4 +- .../src/extern/QGLViewer/VRender/SortMethod.h | 4 +- .../VRender/TopologicalSortMethod.cpp | 186 +- octovis/src/extern/QGLViewer/VRender/Types.h | 4 +- .../src/extern/QGLViewer/VRender/VRender.cpp | 4 +- .../src/extern/QGLViewer/VRender/VRender.h | 13 +- .../src/extern/QGLViewer/VRender/Vector2.cpp | 9 +- .../src/extern/QGLViewer/VRender/Vector2.h | 4 +- .../src/extern/QGLViewer/VRender/Vector3.cpp | 11 +- .../src/extern/QGLViewer/VRender/Vector3.h | 4 +- .../QGLViewer/VRender/VisibilityOptimizer.cpp | 20 +- octovis/src/extern/QGLViewer/VRender/gpc.cpp | 3343 ++++++++--------- octovis/src/extern/QGLViewer/VRender/gpc.h | 70 +- .../extern/QGLViewer/VRenderInterface.Qt3.ui | 211 -- .../src/extern/QGLViewer/VRenderInterface.ui | 34 +- octovis/src/extern/QGLViewer/camera.cpp | 2053 +++++----- octovis/src/extern/QGLViewer/camera.h | 722 ++-- octovis/src/extern/QGLViewer/config.h | 51 +- octovis/src/extern/QGLViewer/constraint.cpp | 301 +- octovis/src/extern/QGLViewer/constraint.h | 372 +- octovis/src/extern/QGLViewer/domUtils.h | 256 +- octovis/src/extern/QGLViewer/frame.cpp | 955 ++--- octovis/src/extern/QGLViewer/frame.h | 571 ++- .../extern/QGLViewer/keyFrameInterpolator.cpp | 902 ++--- .../extern/QGLViewer/keyFrameInterpolator.h | 505 ++- .../QGLViewer/manipulatedCameraFrame.cpp | 610 +-- .../extern/QGLViewer/manipulatedCameraFrame.h | 291 +- .../src/extern/QGLViewer/manipulatedFrame.cpp | 607 +-- .../src/extern/QGLViewer/manipulatedFrame.h | 441 ++- octovis/src/extern/QGLViewer/mouseGrabber.cpp | 34 +- octovis/src/extern/QGLViewer/mouseGrabber.h | 310 +- octovis/src/extern/QGLViewer/qglviewer.cpp | 2232 +++++------ octovis/src/extern/QGLViewer/qglviewer.h | 724 ++-- octovis/src/extern/QGLViewer/qglviewer_fr.qm | Bin 14855 -> 14815 bytes octovis/src/extern/QGLViewer/qglviewer_fr.ts | 24 +- octovis/src/extern/QGLViewer/quaternion.cpp | 514 ++- octovis/src/extern/QGLViewer/quaternion.h | 326 +- octovis/src/extern/QGLViewer/saveSnapshot.cpp | 976 ++--- octovis/src/extern/QGLViewer/vec.cpp | 62 +- octovis/src/extern/QGLViewer/vec.h | 476 ++- 61 files changed, 9161 insertions(+), 10188 deletions(-) delete mode 100644 octovis/src/extern/QGLViewer/ImageInterface.Qt3.ui delete mode 100644 octovis/src/extern/QGLViewer/VRenderInterface.Qt3.ui diff --git a/octovis/src/extern/QGLViewer/CHANGELOG b/octovis/src/extern/QGLViewer/CHANGELOG index c87f72fb..db13655f 100644 --- a/octovis/src/extern/QGLViewer/CHANGELOG +++ b/octovis/src/extern/QGLViewer/CHANGELOG @@ -1,4 +1,4 @@ -This is libQGLViewer version 2.4.0. Packaged on May 28, 2013. +This is libQGLViewer version 2.6.3. Packaged on July 10, 2015. The complete change log is available in doc/changeLog.html diff --git a/octovis/src/extern/QGLViewer/INSTALL b/octovis/src/extern/QGLViewer/INSTALL index 4c3bee6b..c58603af 100644 --- a/octovis/src/extern/QGLViewer/INSTALL +++ b/octovis/src/extern/QGLViewer/INSTALL @@ -3,16 +3,12 @@ -libQGLViewer requires the Qt library, available from Nokia. +libQGLViewer requires the Qt library, available from Digia. -Binary packages are available for different architectures. - - -If you want to compile the library from its sources: +In order to compile the library from its sources: - On UNIX platforms, simply type (see doc/installUnix.html for details): - > cd QGLViewer > qmake > make > make install [optional] diff --git a/octovis/src/extern/QGLViewer/ImageInterface.Qt3.ui b/octovis/src/extern/QGLViewer/ImageInterface.Qt3.ui deleted file mode 100644 index 7ad443fa..00000000 --- a/octovis/src/extern/QGLViewer/ImageInterface.Qt3.ui +++ /dev/null @@ -1,276 +0,0 @@ - -ImageInterface - - - ImageInterface - - - - 0 - 0 - 288 - 213 - - - - Image settings - - - image0 - - - - unnamed - - - - layout5 - - - - unnamed - - - - textLabel1 - - - Width - - - - - imgWidth - - - px - - - 32000 - - - 1 - - - Width of the image (in pixels) - - - - - textLabel2 - - - Height - - - - - imgHeight - - - - - - px - - - 32000 - - - 1 - - - Height of the image (in pixels) - - - - - - - layout2 - - - - unnamed - - - - textLabel3 - - - Image quality - - - - - imgQuality - - - 100 - - - Between 0 (smallest files) and 100 (highest quality) - - - - - spacer1 - - - Horizontal - - - Expanding - - - - 271 - 31 - - - - - - - - layout2_2 - - - - unnamed - - - - textLabel3_2 - - - Oversampling - - - - - - - - oversampling - - - x - - - 64 - - - 1 - - - Antialiases image (when larger then 1.0) - - - - - spacer1_2 - - - Horizontal - - - Expanding - - - - 271 - 31 - - - - - - - - whiteBackground - - - Use white background - - - Use white as background color - - - - - expandFrustum - - - Expand frustum if needed - - - When image aspect ratio differs from viewer's one, expand frustum as needed. Fits inside current frustum otherwise. - - - - - layout4 - - - - unnamed - - - - spacer3 - - - Horizontal - - - Expanding - - - - 251 - 21 - - - - - - pushButton1 - - - OK - - - - - pushButton2 - - - Cancel - - - - - - - - - 89504e470d0a1a0a0000000d494844520000000f000000100806000000c95625040000034b49444154289175936b6c936514c7cf79deb77d7ba1ddda8e6ea173b2b574abb38e0ee59239362b5342829ae8b8242626c6686296201a090924c62fc6208c20972f2c4682f383c449608a805333a633206c7363dd6adacdca6aa117d6ee5ddfbeb7e7f10b8b8a7a92ffb7dfc93f39f91d648cc1ff4d3e9bf55c3edef35e5d207033f4c2d683884819a59c78b9ef65ceb53c0b8cb17f445154e1b75872bd5494cace1c39d6bdd7bf56fef4c5ae1165b1e8648c81387861fb6cfb8a4ceefddd9f100000c61847293300004446e34f9e3df5c39e3bc9d4a34d6d1bbfd9f054c71552282dd765d5060040e7667c8674d24566a71a080083899bb73af279d103005c74ecce0eb3d9a15a6d96a2af2978d1e5ae4a5bcc568918f812008050e949998d027072d144c6a35af8eb6fa73b791ef3aaa23d3017d742de80e757bba36c8669ba41c914aa6d559549de2414000088ae130322f0824521a91cae0cb7fa86ac56733e112b34e7d2ccba2a5831c6f3c68c3c5f58b198487b5dfeba71e439090000b2a94a9e52e0dc9e39be631d77aa58743f44299a2ff5fdbebd6695f3bacb6d8a23a2767772b645992f3a2b560706f1de6d6066aa912001e26d9ce019001d1e8eb445c7d4aed16b0badbbdf6dda050822d5756362e06aa7b9aa22e908ac1c06000031ef86c8c86ab49797b0b1f92782886c3a92aaed39f1e3aba1c7cb07aa6bcd239431393b39d39618fa255cddbee6bc506e9b030060d363eb582c5207b50d71f43d7c9d070068dd18ec076d99bdf1113a29cb258bba20558c9e3cb71f4d8254b379c36944a44cd78cfaa5be9d74513472eb370d80dd91c425c318a37cefd18f0f9890b348e389b5e28d58534b57e707c197b6ec43445d9ff8f969f98d6d9f2141261c3bbb95f88357c8928a8844b3d96cb9feeeded76243e3a19af09a8bf5cfb71f46449d2ee4ddc58fbaf7aae9db76127eee2bac0b5cbdd7f8979ad9db196fcf5b07ce1fddb16b229fcad433c64017179cd943fb4ffe1172e8779f0dddd2e2538f2df178ff63c892e4ecddf366aff7c1eaa8afbe215afaaeff19fdfbfe4d1693a0b8f61d7adbb465db714464ff6a5ecae8b92f5e39d2e0913ff7bbd8a0bf8c4db6d48af3a74fbc435545f83bf79fcb6a495a76edc38387bf7ca2397d63e7e648ee42dfeb545585fbb93f01b22dcb16d181190d0000000049454e44ae426082 - - - - - pushButton1 - clicked() - ImageInterface - accept() - - - pushButton2 - clicked() - ImageInterface - reject() - - - - diff --git a/octovis/src/extern/QGLViewer/LICENCE b/octovis/src/extern/QGLViewer/LICENCE index fe654178..441a6877 100644 --- a/octovis/src/extern/QGLViewer/LICENCE +++ b/octovis/src/extern/QGLViewer/LICENCE @@ -1037,4 +1037,4 @@ Public License instead of this License. But first, please read ------------------------------------------------------------------------- - The QGLViewer library is Copyright (C) 2002-2013 Gilles Debunne. + The QGLViewer library is Copyright (C) 2002-2014 Gilles Debunne. diff --git a/octovis/src/extern/QGLViewer/QGLViewer.pro b/octovis/src/extern/QGLViewer/QGLViewer.pro index 5093e6e5..8210248a 100644 --- a/octovis/src/extern/QGLViewer/QGLViewer.pro +++ b/octovis/src/extern/QGLViewer/QGLViewer.pro @@ -4,13 +4,9 @@ # Run "qmake; make; make install" to compile and install the library on Unix systems. # Optional arguments can tune install paths (as in "qmake PREFIX=$HOME"). See doc/download.html for details. -# If your Qt version is lower than 3.1 (look at $QTDIR/lib), you need to link with GLUT. -# Uncomment the following line: -# USE_GLUT = yes - TEMPLATE = lib TARGET = QGLViewer -VERSION = 2.4.0 +VERSION = 2.6.3 CONFIG *= qt opengl warn_on shared thread create_prl rtti no_keywords QGL_HEADERS = qglviewer.h \ @@ -40,17 +36,14 @@ SOURCES = qglviewer.cpp \ HEADERS *= $${QGL_HEADERS} DISTFILES *= qglviewer-icon.xpm +DESTDIR = $${PWD} TRANSLATIONS = qglviewer_fr.ts - -QT_VERSION=$$[QT_VERSION] -!contains( QT_VERSION, "^3.*" ) { - QT *= xml opengl -} +QT *= xml opengl -contains ( QT_VERSION, "^5.*" ) { - QT *= widgets +contains ( $$[QT_VERSION], "^5.*" ) { + QT *= gui widgets } !isEmpty( QGLVIEWER_STATIC ) { @@ -60,11 +53,7 @@ contains ( QT_VERSION, "^5.*" ) { # ----------------------------------- # -- I m a g e I n t e r f a c e -- # ----------------------------------- -contains( QT_VERSION, "^3.*" ) { - FORMS *= ImageInterface.Qt3.ui -} else { - FORMS *= ImageInterface.ui -} +FORMS *= ImageInterface.ui # --------------------------------------------- # -- V e c t o r i a l R e n d e r i n g -- @@ -75,11 +64,7 @@ contains( QT_VERSION, "^3.*" ) { contains( DEFINES, NO_VECTORIAL_RENDER ) { message( Vectorial rendering disabled ) } else { - contains( QT_VERSION, "^3.*" ) { - FORMS *= VRenderInterface.Qt3.ui - } else { - FORMS *= VRenderInterface.ui - } + FORMS *= VRenderInterface.ui SOURCES *= \ VRender/BackFaceCullingOptimizer.cpp \ @@ -117,120 +102,97 @@ contains( DEFINES, NO_VECTORIAL_RENDER ) { } - - # --------------- # -- U n i x -- # --------------- unix { - CONFIG -= debug debug_and_release - CONFIG *= release - - # INCLUDE_DIR and LIB_DIR specify where to install the include files and the library. - # Use qmake INCLUDE_DIR=... LIB_DIR=... , or qmake PREFIX=... to customize your installation. - - HOME_DIR = $$system(cd;pwd) - - isEmpty( PREFIX ) { - PREFIX_=/usr - } else { - PREFIX_=$${PREFIX} - } - isEmpty( LIB_DIR ) { - LIB_DIR_ = $${PREFIX_}/lib - } else { - LIB_DIR_ = $${LIB_DIR} - } - isEmpty( INCLUDE_DIR ) { - INCLUDE_DIR_ = $${PREFIX_}/include - } else { - INCLUDE_DIR_ = $${INCLUDE_DIR} - } - isEmpty( DOC_DIR ) { - macx|darwin-g++ { - isEmpty( PREFIX ) { - DOC_DIR = $${HOME_DIR}/Library/Developer/Shared/Documentation/QGLViewer - } else { - DOC_DIR = $${PREFIX}/Shared/Documentation/QGLViewer - } - } else { - DOC_DIR = $${PREFIX_}/share/doc/QGLViewer - } - } - - # GLUT for Unix architecture - !isEmpty( USE_GLUT ) { - QMAKE_LIBS_OPENGL *= -lglut - } - - MOC_DIR = .moc - OBJECTS_DIR = .obj - - # Adds a -P option so that "make install" as root creates files owned by root and links are preserved. - # This is not a standard option, and it may have to be removed on old Unix flavors. - !hpux { - QMAKE_COPY_FILE = $${QMAKE_COPY_FILE} -P - } - - # Make much smaller libraries (and packages) by removing debugging informations - QMAKE_CFLAGS_RELEASE -= -g - QMAKE_CXXFLAGS_RELEASE -= -g - - # install header - include.path = $${INCLUDE_DIR_}/QGLViewer - # Should be $$replace(TRANSLATIONS, .ts, .qm), but 'replace' only appeared in Qt 4.3 - include.files = $${QGL_HEADERS} qglviewer_fr.qm - - # install documentation html - documentation.path = $${DOC_DIR} - documentation.files = ../doc/*.html ../doc/*.css ../doc/*.qch - - # install documentation images - docImages.path = $${DOC_DIR}/images - docImages.files = ../doc/images/* - - # install documentation examples - #docExamples.path = $${DOC_DIR}/examples - #docExamples.files = ../examples/*../examples/*/* - - # install documentation refManual - docRefManual.path = $${DOC_DIR}/refManual - docRefManual.files = ../doc/refManual/* - - # install static library - #staticlib.extra = make -f Makefile.Release staticlib - #staticlib.path = $${LIB_DIR_} - #staticlib.files = lib$${TARGET}.a - - # install library - target.path = $${LIB_DIR_} - - # "make install" configuration options - INSTALLS *= target include documentation docImages docRefManual -} - - -# ----------------------- -# -- S G I I r i x -- -# ----------------------- -irix-cc|irix-n32 { - QMAKE_CFLAGS_RELEASE -= -O3 -O2 -OPT:Olimit=30000 - QMAKE_LFLAGS_RELEASE -= -O3 -O2 -OPT:Olimit=30000 - QMAKE_CXXFLAGS_RELEASE -= -O3 -O2 -OPT:Olimit=30000 - QMAKE_CFLAGS_RELEASE *= -IPA -Ofast=IP35 - QMAKE_LFLAGS_RELEASE *= -IPA -Ofast=IP35 - QMAKE_CXXFLAGS_RELEASE *= -IPA -Ofast=IP35 - QMAKE_CFLAGS *= -LANG:std - QMAKE_LFLAGS *= -LANG:std - QMAKE_CXXFLAGS *= -LANG:std - QMAKE_CFLAGS *= -woff 1424,3201,1110,1188 - QMAKE_CXXFLAGS *= -woff 1424,3201,1110,1188 - QMAKE_LIBS_OPENGL -= -lXi - # GLUT for SGI architecture - !isEmpty( USE_GLUT ) { - QMAKE_LIBDIR_OPENGL *= /usr/local/lib32 - QMAKE_INCDIR_OPENGL *= /usr/local/include - } + CONFIG -= debug debug_and_release + CONFIG *= release + + # INCLUDE_DIR and LIB_DIR specify where to install the include files and the library. + # Use qmake INCLUDE_DIR=... LIB_DIR=... , or qmake PREFIX=... to customize your installation. + isEmpty( PREFIX ) { + PREFIX_=/usr/local + } else { + PREFIX_=$${PREFIX} + } + isEmpty( LIB_DIR ) { + LIB_DIR_ = $${PREFIX_}/lib + } else { + LIB_DIR_ = $${LIB_DIR} + } + isEmpty( INCLUDE_DIR ) { + INCLUDE_DIR_ = $${PREFIX_}/include + } else { + INCLUDE_DIR_ = $${INCLUDE_DIR} + } + isEmpty( DOC_DIR ) { + macx|darwin-g++ { + isEmpty( PREFIX ) { + DOC_DIR = $${PWD}/Library/Developer/Shared/Documentation/QGLViewer + } else { + DOC_DIR = $${PREFIX}/Shared/Documentation/QGLViewer + } + } else { + DOC_DIR = $${PREFIX_}/share/doc/QGLViewer + } + } + + # GLUT for Unix architecture + !isEmpty( USE_GLUT ) { + QMAKE_LIBS_OPENGL *= -lglut + } + + macx|darwin-g++ { + # GLU is part of the OpenGL framework + } else { + QMAKE_LIBS_OPENGL *= -lGLU + } + + MOC_DIR = .moc + OBJECTS_DIR = .obj + + # Adds a -P option so that "make install" as root creates files owned by root and links are preserved. + # This is not a standard option, and it may have to be removed on old Unix flavors. + !hpux { + QMAKE_COPY_FILE = $${QMAKE_COPY_FILE} -P + } + + # Make much smaller libraries (and packages) by removing debugging informations + QMAKE_CFLAGS_RELEASE -= -g + QMAKE_CXXFLAGS_RELEASE -= -g + + # install header + include.path = $${INCLUDE_DIR_}/QGLViewer + # Should be $$replace(TRANSLATIONS, .ts, .qm), but 'replace' only appeared in Qt 4.3 + include.files = $${QGL_HEADERS} qglviewer_fr.qm + + # install documentation html + documentation.path = $${DOC_DIR} + documentation.files = ../doc/*.html ../doc/*.css ../doc/*.qch + + # install documentation images + docImages.path = $${DOC_DIR}/images + docImages.files = ../doc/images/* + + # install documentation examples + #docExamples.path = $${DOC_DIR}/examples + #docExamples.files = ../examples/*../examples/*/* + + # install documentation refManual + docRefManual.path = $${DOC_DIR}/refManual + docRefManual.files = ../doc/refManual/* + + # install static library + #staticlib.extra = make -f Makefile.Release staticlib + #staticlib.path = $${LIB_DIR_} + #staticlib.files = lib$${TARGET}.a + + # install library + target.path = $${LIB_DIR_} + + # "make install" configuration options + INSTALLS *= target include documentation docImages docRefManual } @@ -238,53 +200,35 @@ irix-cc|irix-n32 { # -- M a c O S X -- # ------------------- macx|darwin-g++ { - # This setting creates a Mac framework. Comment out this line to create a dylib instead. - !staticlib: CONFIG *= lib_bundle - - include.files *= qglviewer.icns - - lib_bundle { - FRAMEWORK_HEADERS.version = Versions - # Should be $$replace(TRANSLATIONS, .ts, .qm), but 'replace' is only available in Qt 4.3 - FRAMEWORK_HEADERS.files = $${QGL_HEADERS} qglviewer.icns qglviewer_fr.qm - FRAMEWORK_HEADERS.path = Headers - QMAKE_BUNDLE_DATA += FRAMEWORK_HEADERS - - DESTDIR = $${HOME_DIR}/Library/Frameworks/ - - # For a Framework, 'include' and 'lib' do no make sense. - # These and prefix will all define the DESTDIR, in that order in case several are defined - !isEmpty( INCLUDE_DIR ) { - DESTDIR = $${INCLUDE_DIR} - } - - !isEmpty( LIB_DIR ) { - DESTDIR = $${LIB_DIR} - } - - !isEmpty( PREFIX ) { - DESTDIR = $${PREFIX} - } - - QMAKE_POST_LINK=cd $$DESTDIR/QGLViewer.framework/Headers && (test -L QGLViewer || ln -s . QGLViewer) - - #QMAKE_LFLAGS_SONAME = -Wl,-install_name,@executable_path/../Frameworks/ - #QMAKE_LFLAGS_SONAME = -Wl,-install_name, - - # Framework already installed, with includes - INSTALLS -= include target - } else { - #QMAKE_LFLAGS_SONAME = -Wl,-install_name,libQGLViewer.dylib - } - - # GLUT for Macintosh architecture - !isEmpty( USE_GLUT ) { - QMAKE_LIBS_OPENGL -= -lglut - QMAKE_LIBS_OPENGL *= -framework GLUT -lobjc - } - - # Qt3 only - macx: CONFIG -= thread + # This setting creates a Mac framework. Comment out this line to create a dylib instead. + !staticlib: CONFIG *= lib_bundle + + include.files *= qglviewer.icns + + lib_bundle { + FRAMEWORK_HEADERS.version = Versions + # Should be $$replace(TRANSLATIONS, .ts, .qm), but 'replace' is only available in Qt 4.3 + FRAMEWORK_HEADERS.files = $${QGL_HEADERS} qglviewer.icns qglviewer_fr.qm + FRAMEWORK_HEADERS.path = Headers + QMAKE_BUNDLE_DATA += FRAMEWORK_HEADERS + + # So that the path QGLViewer/*.h exists + QMAKE_POST_LINK=cd $$DESTDIR/QGLViewer.framework/Headers && (test -L QGLViewer || ln -s . QGLViewer) + + # Specific paths for the installation of the framework. + !isEmpty( LIB_DIR ) { + target.path = $${LIB_DIR} + } + + # Framework already contains includes + INSTALLS -= include + } + + # GLUT for Mac architecture + !isEmpty( USE_GLUT ) { + QMAKE_LIBS_OPENGL -= -lglut + QMAKE_LIBS_OPENGL *= -framework GLUT -lobjc + } } @@ -292,41 +236,44 @@ macx|darwin-g++ { # -- W i n d o w s -- # --------------------- win32 { - # Windows requires a debug lib version to link against debug applications - CONFIG *= debug_and_release build_all - - # Needed by Intel C++, (icl.exe) so that WINGDIAPI is a defined symbol in gl.h. - DEFINES *= WIN32 - - staticlib { - DEFINES *= QGLVIEWER_STATIC - } else { - DEFINES *= CREATE_QGLVIEWER_DLL - } - - # Use the DLL version of Qt (Qt3 only) - DEFINES *= QT_DLL QT_THREAD_SUPPORT - - CONFIG *= embed_manifest_dll - - # Make sure to have C++ files, PentiumPro code, few warnings, add - # support to RTTI and Exceptions, and generate debug info "program database". - # Any feedback on these flags is welcome. - !win32-g++ { - QMAKE_CXXFLAGS = -TP -GR -Zi - DEFINES += NOMINMAX - win32-msvc { - QMAKE_CXXFLAGS *= -GX - } else { - QMAKE_CXXFLAGS *= -EHs - } - } + # Windows requires a debug lib version to link against debug applications + CONFIG *= debug_and_release build_all + + # Needed by Intel C++, (icl.exe) so that WINGDIAPI is a defined symbol in gl.h. + DEFINES *= WIN32 + + staticlib { + DEFINES *= QGLVIEWER_STATIC + } else { + DEFINES *= CREATE_QGLVIEWER_DLL + } + + CONFIG *= embed_manifest_dll + + # Use native OpenGL drivers with Qt5.5 + # No longer implicit since the ANGLE driver is now an alternative + LIBS += -lopengl32 -lglu32 + + # TP : C++ source code + # GR : Enables run-time type information (RTTI). + # Zi : Generates complete debugging information (removed) + # EHs : The exception-handling model that catches C++ exceptions only and tells the + # compiler to assume that functions declared as extern "C" may throw an exception. + # FS : Enable parallel compilation + # Any feedback on these flags is welcome. + !win32-g++ { + QMAKE_CXXFLAGS *= -TP -GR + DEFINES += NOMINMAX + win32-msvc { + QMAKE_CXXFLAGS *= -EH -FS + } else { + QMAKE_CXXFLAGS *= -EHs + } + } } -!contains( QT_VERSION, "^3.*" ) { - build_pass:CONFIG(debug, debug|release) { - unix: TARGET = $$join(TARGET,,,_debug) - else: TARGET = $$join(TARGET,,,d) - } +build_pass:CONFIG(debug, debug|release) { + unix: TARGET = $$join(TARGET,,,_debug) + else: TARGET = $$join(TARGET,,,d) } diff --git a/octovis/src/extern/QGLViewer/README b/octovis/src/extern/QGLViewer/README index 4dd7b3d5..44f36292 100644 --- a/octovis/src/extern/QGLViewer/README +++ b/octovis/src/extern/QGLViewer/README @@ -1,10 +1,10 @@ l i b Q G L V i e w e r - Version 2.4.0. Packaged on May 28, 2013 + Version 2.6.3. Packaged on July 10, 2015 - Copyright (C) 2002-2013 Gilles Debunne. All rights reserved. + Copyright (C) 2002-2014 Gilles Debunne. All rights reserved. http://www.libqglviewer.com Send e-mail to contact@libqglviewer.com diff --git a/octovis/src/extern/QGLViewer/VRender/AxisAlignedBox.h b/octovis/src/extern/QGLViewer/VRender/AxisAlignedBox.h index 84a0c55f..db401fd4 100644 --- a/octovis/src/extern/QGLViewer/VRender/AxisAlignedBox.h +++ b/octovis/src/extern/QGLViewer/VRender/AxisAlignedBox.h @@ -22,9 +22,9 @@ /**************************************************************************** - Copyright (C) 2002-2013 Gilles Debunne. All rights reserved. + Copyright (C) 2002-2014 Gilles Debunne. All rights reserved. - This file is part of the QGLViewer library version 2.4.0. + This file is part of the QGLViewer library version 2.6.3. http://www.libqglviewer.com - contact@libqglviewer.com diff --git a/octovis/src/extern/QGLViewer/VRender/BSPSortMethod.cpp b/octovis/src/extern/QGLViewer/VRender/BSPSortMethod.cpp index 7aa69379..7d436815 100644 --- a/octovis/src/extern/QGLViewer/VRender/BSPSortMethod.cpp +++ b/octovis/src/extern/QGLViewer/VRender/BSPSortMethod.cpp @@ -22,9 +22,9 @@ /**************************************************************************** - Copyright (C) 2002-2013 Gilles Debunne. All rights reserved. + Copyright (C) 2002-2014 Gilles Debunne. All rights reserved. - This file is part of the QGLViewer library version 2.4.0. + This file is part of the QGLViewer library version 2.6.3. http://www.libqglviewer.com - contact@libqglviewer.com diff --git a/octovis/src/extern/QGLViewer/VRender/BackFaceCullingOptimizer.cpp b/octovis/src/extern/QGLViewer/VRender/BackFaceCullingOptimizer.cpp index 00e9a429..3cc08689 100644 --- a/octovis/src/extern/QGLViewer/VRender/BackFaceCullingOptimizer.cpp +++ b/octovis/src/extern/QGLViewer/VRender/BackFaceCullingOptimizer.cpp @@ -22,9 +22,9 @@ /**************************************************************************** - Copyright (C) 2002-2013 Gilles Debunne. All rights reserved. + Copyright (C) 2002-2014 Gilles Debunne. All rights reserved. - This file is part of the QGLViewer library version 2.4.0. + This file is part of the QGLViewer library version 2.6.3. http://www.libqglviewer.com - contact@libqglviewer.com @@ -58,10 +58,10 @@ void BackFaceCullingOptimizer::optimize(std::vector& primitives_ta Polygone *P ; int nb_culled = 0 ; - for(unsigned int i=0;i(primitives_tab[i])) != NULL) { - for(unsigned int j=0;jnbVertices();++j) + for(unsigned int j=0;jnbVertices();++j) if(( (P->vertex(j+2) - P->vertex(j+1))^(P->vertex(j+1) - P->vertex(j))).z() > 0.0 ) { delete primitives_tab[i] ; @@ -74,7 +74,7 @@ void BackFaceCullingOptimizer::optimize(std::vector& primitives_ta // Rule out gaps. This avoids testing for null primitives later. int j=0 ; - for(unsigned int k=0;k= 0x040000 -# include -# include -#else -# include -# include -#endif +#include +#include using namespace vrender ; using namespace std ; @@ -69,11 +64,7 @@ void Exporter::exportToFile(const QString& filename, { QFile file(filename); -#if QT_VERSION >= 0x040000 if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) { -#else - if (!file.open(IO_WriteOnly | IO_Translate)) { -#endif QMessageBox::warning(NULL, QGLViewer::tr("Exporter error", "Message box window title"), QGLViewer::tr("Unable to open file %1.").arg(filename)); return; } @@ -82,7 +73,7 @@ void Exporter::exportToFile(const QString& filename, writeHeader(out) ; - unsigned int N = primitive_tab.size()/200 + 1 ; + unsigned int N = primitive_tab.size()/200 + 1 ; for(unsigned int i=0;i= 0x040000 -# include -# include -#else -# include -# include -#endif +#include +#include namespace vrender { diff --git a/octovis/src/extern/QGLViewer/VRender/FIGExporter.cpp b/octovis/src/extern/QGLViewer/VRender/FIGExporter.cpp index 85f58242..b7411586 100644 --- a/octovis/src/extern/QGLViewer/VRender/FIGExporter.cpp +++ b/octovis/src/extern/QGLViewer/VRender/FIGExporter.cpp @@ -22,9 +22,9 @@ /**************************************************************************** - Copyright (C) 2002-2013 Gilles Debunne. All rights reserved. + Copyright (C) 2002-2014 Gilles Debunne. All rights reserved. - This file is part of the QGLViewer library version 2.4.0. + This file is part of the QGLViewer library version 2.6.3. http://www.libqglviewer.com - contact@libqglviewer.com diff --git a/octovis/src/extern/QGLViewer/VRender/NVector3.cpp b/octovis/src/extern/QGLViewer/VRender/NVector3.cpp index d59d5366..80864a90 100644 --- a/octovis/src/extern/QGLViewer/VRender/NVector3.cpp +++ b/octovis/src/extern/QGLViewer/VRender/NVector3.cpp @@ -22,9 +22,9 @@ /**************************************************************************** - Copyright (C) 2002-2013 Gilles Debunne. All rights reserved. + Copyright (C) 2002-2014 Gilles Debunne. All rights reserved. - This file is part of the QGLViewer library version 2.4.0. + This file is part of the QGLViewer library version 2.6.3. http://www.libqglviewer.com - contact@libqglviewer.com diff --git a/octovis/src/extern/QGLViewer/VRender/NVector3.h b/octovis/src/extern/QGLViewer/VRender/NVector3.h index 5501fef9..cac62e47 100644 --- a/octovis/src/extern/QGLViewer/VRender/NVector3.h +++ b/octovis/src/extern/QGLViewer/VRender/NVector3.h @@ -22,9 +22,9 @@ /**************************************************************************** - Copyright (C) 2002-2013 Gilles Debunne. All rights reserved. + Copyright (C) 2002-2014 Gilles Debunne. All rights reserved. - This file is part of the QGLViewer library version 2.4.0. + This file is part of the QGLViewer library version 2.6.3. http://www.libqglviewer.com - contact@libqglviewer.com diff --git a/octovis/src/extern/QGLViewer/VRender/Optimizer.h b/octovis/src/extern/QGLViewer/VRender/Optimizer.h index ea2ddb7e..be344b4d 100644 --- a/octovis/src/extern/QGLViewer/VRender/Optimizer.h +++ b/octovis/src/extern/QGLViewer/VRender/Optimizer.h @@ -22,9 +22,9 @@ /**************************************************************************** - Copyright (C) 2002-2013 Gilles Debunne. All rights reserved. + Copyright (C) 2002-2014 Gilles Debunne. All rights reserved. - This file is part of the QGLViewer library version 2.4.0. + This file is part of the QGLViewer library version 2.6.3. http://www.libqglviewer.com - contact@libqglviewer.com diff --git a/octovis/src/extern/QGLViewer/VRender/ParserGL.cpp b/octovis/src/extern/QGLViewer/VRender/ParserGL.cpp index 11300ca2..4afe15db 100644 --- a/octovis/src/extern/QGLViewer/VRender/ParserGL.cpp +++ b/octovis/src/extern/QGLViewer/VRender/ParserGL.cpp @@ -22,9 +22,9 @@ /**************************************************************************** - Copyright (C) 2002-2013 Gilles Debunne. All rights reserved. + Copyright (C) 2002-2014 Gilles Debunne. All rights reserved. - This file is part of the QGLViewer library version 2.4.0. + This file is part of the QGLViewer library version 2.6.3. http://www.libqglviewer.com - contact@libqglviewer.com @@ -221,9 +221,9 @@ PtrPrimitive ParserUtils::checkPolygon(Polygone *& P) { // On ne traite que le cas du triangle plat, vu qu'on est sur d'avoir un triangle - int n = P->nbVertices() ; + size_t n = P->nbVertices() ; - for(int i=0;ivertex(i) - P->vertex((i+1)%n)).norm() > EGALITY_EPS) { Segment *pp = new Segment(P->sommet3DColor((i+1)%n),P->sommet3DColor((i+2)%n)) ; @@ -250,10 +250,8 @@ PtrPrimitive ParserUtils::checkPolygon(Polygone *& P) void ParserUtils::print3DcolorVertex(GLint size, GLint * count, GLfloat * buffer) { - int i; - printf(" "); - for (i = 0; i < Feedback3DColor::sizeInBuffer(); i++) + for (size_t i = 0; i < Feedback3DColor::sizeInBuffer(); i++) { printf("%4.2f ", buffer[size - (*count)]); *count = *count - 1; diff --git a/octovis/src/extern/QGLViewer/VRender/ParserGL.h b/octovis/src/extern/QGLViewer/VRender/ParserGL.h index cfdd2c54..2374a787 100644 --- a/octovis/src/extern/QGLViewer/VRender/ParserGL.h +++ b/octovis/src/extern/QGLViewer/VRender/ParserGL.h @@ -22,9 +22,9 @@ /**************************************************************************** - Copyright (C) 2002-2013 Gilles Debunne. All rights reserved. + Copyright (C) 2002-2014 Gilles Debunne. All rights reserved. - This file is part of the QGLViewer library version 2.4.0. + This file is part of the QGLViewer library version 2.6.3. http://www.libqglviewer.com - contact@libqglviewer.com diff --git a/octovis/src/extern/QGLViewer/VRender/Primitive.cpp b/octovis/src/extern/QGLViewer/VRender/Primitive.cpp index 79d77f91..b7c27238 100644 --- a/octovis/src/extern/QGLViewer/VRender/Primitive.cpp +++ b/octovis/src/extern/QGLViewer/VRender/Primitive.cpp @@ -22,9 +22,9 @@ /**************************************************************************** - Copyright (C) 2002-2013 Gilles Debunne. All rights reserved. + Copyright (C) 2002-2014 Gilles Debunne. All rights reserved. - This file is part of the QGLViewer library version 2.4.0. + This file is part of the QGLViewer library version 2.6.3. http://www.libqglviewer.com - contact@libqglviewer.com @@ -50,22 +50,23 @@ using namespace vrender ; using namespace std ; + Point::Point(const Feedback3DColor& f) : _position_and_color(f) { } -const Vector3& Point::vertex(int) const +const Vector3& Point::vertex(size_t) const { return _position_and_color.pos() ; } -const Feedback3DColor& Point::sommet3DColor(int) const +const Feedback3DColor& Point::sommet3DColor(size_t) const { return _position_and_color ; } -const Feedback3DColor& Segment::sommet3DColor(int i) const +const Feedback3DColor& Segment::sommet3DColor(size_t i) const { return ( (i&1)==0 )?P1:P2 ; } @@ -75,7 +76,7 @@ AxisAlignedBox_xyz Point::bbox() const return AxisAlignedBox_xyz(_position_and_color.pos(),_position_and_color.pos()) ; } -const Vector3& Segment::vertex(int i) const +const Vector3& Segment::vertex(size_t i) const { return ( (i&1)==0 )?P1.pos():P2.pos() ; } @@ -88,12 +89,12 @@ AxisAlignedBox_xyz Segment::bbox() const return B ; } -const Feedback3DColor& Polygone::sommet3DColor(int i) const +const Feedback3DColor& Polygone::sommet3DColor(size_t i) const { return _vertices[i % nbVertices()] ; } -const Vector3& Polygone::vertex(int i) const +const Vector3& Polygone::vertex(size_t i) const { return _vertices[i % nbVertices()].pos() ; } @@ -104,7 +105,7 @@ Polygone::Polygone(const vector& fc) { initNormal() ; - for(unsigned int i=0;i&) ; - virtual ~Polygone() {} + class Polygone: public Primitive + { + public: + Polygone(const std::vector&) ; + virtual ~Polygone() {} #ifdef A_FAIRE - virtual int IsAPolygon() { return 1 ; } - virtual void Split(const Vector3&,FLOAT,Primitive * &,Primitive * &) ; - void InitEquation(double &,double &,double &,double &) ; + virtual int IsAPolygon() { return 1 ; } + virtual void Split(const Vector3&,FLOAT,Primitive * &,Primitive * &) ; + void InitEquation(double &,double &,double &,double &) ; #endif - virtual const Feedback3DColor& sommet3DColor(int) const ; - virtual const Vector3& vertex(int) const ; - virtual unsigned int nbVertices() const { return _vertices.size() ; } - virtual AxisAlignedBox_xyz bbox() const ; - double equation(const Vector3& p) const ; - const NVector3& normal() const { return _normal ; } - double c() const { return _c ; } + virtual const Feedback3DColor& sommet3DColor(size_t) const ; + virtual const Vector3& vertex(size_t) const ; + virtual size_t nbVertices() const { return _vertices.size() ; } + virtual AxisAlignedBox_xyz bbox() const ; + double equation(const Vector3& p) const ; + const NVector3& normal() const { return _normal ; } + double c() const { return _c ; } - FLOAT FlatFactor() const { return anglefactor ; } + FLOAT FlatFactor() const { return anglefactor ; } protected: - virtual void initNormal() ; - void CheckInfoForPositionOperators() ; - - AxisAlignedBox_xyz _bbox ; - std::vector _vertices ; - // std::vector _sommetsProjetes ; - // Vector3 N,M,L ; - double anglefactor ; // Determine a quel point un polygone est plat. - // Comparer a FLAT_POLYGON_EPS - double _c ; - NVector3 _normal ; - } ; + virtual void initNormal() ; + void CheckInfoForPositionOperators() ; + + AxisAlignedBox_xyz _bbox ; + std::vector _vertices ; + // std::vector _sommetsProjetes ; + // Vector3 N,M,L ; + double anglefactor ; // Determine a quel point un polygone est plat. + // Comparer a FLAT_POLYGON_EPS + double _c ; + NVector3 _normal ; + } ; } #endif diff --git a/octovis/src/extern/QGLViewer/VRender/PrimitivePositioning.cpp b/octovis/src/extern/QGLViewer/VRender/PrimitivePositioning.cpp index a8a900a6..072d45c9 100644 --- a/octovis/src/extern/QGLViewer/VRender/PrimitivePositioning.cpp +++ b/octovis/src/extern/QGLViewer/VRender/PrimitivePositioning.cpp @@ -22,9 +22,9 @@ /**************************************************************************** - Copyright (C) 2002-2013 Gilles Debunne. All rights reserved. + Copyright (C) 2002-2014 Gilles Debunne. All rights reserved. - This file is part of the QGLViewer library version 2.4.0. + This file is part of the QGLViewer library version 2.6.3. http://www.libqglviewer.com - contact@libqglviewer.com @@ -42,55 +42,15 @@ *****************************************************************************/ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - #include "Primitive.h" #include "AxisAlignedBox.h" #include "PrimitivePositioning.h" #include "math.h" +#include #include "Vector2.h" +#include + using namespace vrender ; using namespace std ; @@ -168,7 +128,7 @@ int PrimitivePositioning::computeRelativePosition(const Polygone *P,const Segmen double t1,t2 ; - for(unsigned int i=0;inbVertices();++i) + for(size_t i=0;inbVertices();++i) if(intersectSegments_XY(Vector2(S->vertex(0)),Vector2(S->vertex(1)),Vector2(P->vertex(i)),Vector2(P->vertex(i+1)),_EPS,t1,t2)) intersections.push_back(t1) ; @@ -180,8 +140,8 @@ int PrimitivePositioning::computeRelativePosition(const Polygone *P,const Segmen for(unsigned int j=0;jnormal().z() == 0.0) throw runtime_error("could not project point. Unexpected case !") ; if(P2->normal().z() == 0.0) throw runtime_error("could not project point. Unexpected case !") ; @@ -298,21 +258,21 @@ int PrimitivePositioning::computeRelativePosition(const Segment *S1,const Segmen bool PrimitivePositioning::pointOutOfPolygon_XY(const Vector3& P,const Polygone *Q,double I_EPS) { - int nq = Q->nbVertices() ; + size_t nq = Q->nbVertices() ; Vector2 p = Vector2(P) ; FLOAT MaxZ = -FLT_MAX ; FLOAT MinZ = FLT_MAX ; - for(int j=0;jvertex(j)) ; Vector2 q2 = Vector2(Q->vertex(j+1)) ; double Z = (q1-p)^(q2-p) ; - MinZ = min(Z,MinZ) ; - MaxZ = max(Z,MaxZ) ; + MinZ = std::min(Z,MinZ) ; + MaxZ = std::max(Z,MaxZ) ; } if((MaxZ <= -I_EPS*I_EPS)||(MinZ >= I_EPS*I_EPS)) // the point is inside the polygon @@ -392,8 +352,8 @@ bool PrimitivePositioning::intersectSegments_XY(const Vector2& P1,const Vector2& return false ; } - double tPQM = max(tP1,tQ1) ; - double tPQm = min(tP1,tQ1) ; + double tPQM = std::max(tP1,tQ1) ; + double tPQm = std::min(tP1,tQ1) ; if(( tPQM < -I_EPS) || (tPQm > 1.0+I_EPS)) return false ; @@ -447,7 +407,7 @@ gpc_polygon PrimitivePositioning::createGPCPolygon_XY(const Polygone *P) gpc_p_verts->num_vertices = P->nbVertices() ; gpc_p_verts->vertex = new gpc_vertex[P->nbVertices()] ; - for(unsigned int i=0;inbVertices();++i) + for(size_t i=0;inbVertices();++i) { gpc_p_verts->vertex[i].x = P->vertex(i).x() ; gpc_p_verts->vertex[i].y = P->vertex(i).y() ; @@ -464,7 +424,7 @@ void PrimitivePositioning::getsigns(const Primitive *P,const NVector3& v,double if(P == NULL) throw runtime_error("Null primitive in getsigns !") ; - int n = P->nbVertices() ; + size_t n = P->nbVertices() ; Smin = 1 ; Smax = -1 ; @@ -475,7 +435,7 @@ void PrimitivePositioning::getsigns(const Primitive *P,const NVector3& v,double double zmin = FLT_MAX ; zvals.resize(n) ; - for(int i=0;ivertex(i) * v - C ; @@ -487,7 +447,7 @@ void PrimitivePositioning::getsigns(const Primitive *P,const NVector3& v,double signs.resize(n) ; - for(int j=0;jnbVertices() ; + size_t n = P->nbVertices() ; if((Smin == 0)&&(Smax == 0)){ P_moins = P ; P_plus = NULL ; return ; } // Polygone inclus dans le plan if(Smin == 1) { P_plus = P ; P_moins = NULL ; return ; } // Polygone tout positif @@ -533,7 +493,7 @@ void PrimitivePositioning::split(Polygone *P,const NVector3& v,double C,Primitiv int nZero = 0 ; int nconsZero = 0 ; - for(int i=0;inbVertices() ; + size_t n = S->nbVertices() ; if((Smin == 0)&&(Smax == 0)) { P_moins = S ; P_plus = NULL ; return ; } // Polygone inclus dans le plan if(Smin == 1) { P_plus = S ; P_moins = NULL ; return ; } // Polygone tout positif @@ -660,7 +620,7 @@ void PrimitivePositioning::split(Segment *S,const NVector3& v,double C,Primitive int nZero = 0 ; int nconsZero = 0 ; - for(int i=0;i& primitive_tab, vector< vector >& precedence_graph) ; + static void buildPrecedenceGraph(vector& primitive_tab, vector< vector >& precedence_graph) ; static void recursFindNeighbors( const vector& primitive_tab, - const vector& pindices, - vector< vector >& precedence_graph, + const vector& pindices, + vector< vector >& precedence_graph, const AxisAlignedBox_xy&,int) ; - static void checkAndAddEdgeToGraph(int a,int b,vector< vector >& precedence_graph) ; - static void suppressPrecedence(int a,int b,vector< vector >& precedence_graph) ; + static void checkAndAddEdgeToGraph(size_t a,size_t b,vector< vector >& precedence_graph) ; + static void suppressPrecedence(size_t a,size_t b,vector< vector >& precedence_graph) ; - static void recursTopologicalSort(vector< vector >& precedence_graph, + static void recursTopologicalSort(vector< vector >& precedence_graph, vector& primitive_tab, vector& alread_rendered, vector& alread_visited, - vector&,int,int&, + vector&,size_t,size_t&, VRenderParams& vparams, - int info_cnt,int& nbrendered) ; + size_t info_cnt,size_t& nbrendered) ; - static void recursTopologicalSort(vector< vector >& precedence_graph, + static void recursTopologicalSort(vector< vector >& precedence_graph, vector& primitive_tab, vector& alread_rendered, vector& alread_visited, - vector&,int, - vector& ancestors, - int&, int&, + vector&,size_t, + vector& ancestors, + size_t&, size_t&, VRenderParams& vparams, - int info_cnt,int& nbrendered) ; + size_t info_cnt,size_t& nbrendered) ; - static void topologicalSort( vector< vector >& precedence_graph, + static void topologicalSort( vector< vector >& precedence_graph, vector& primitive_tab, VRenderParams&) ; - static void topologicalSortBreakCycles(vector< vector >& precedence_graph, + static void topologicalSortBreakCycles(vector< vector >& precedence_graph, vector& primitive_tab, VRenderParams&) ; #ifdef DEBUG_TS - static void printPrecedenceGraph(const vector< vector >& precedence_graph, + static void printPrecedenceGraph(const vector< vector >& precedence_graph, const vector& primitive_tab) ; #endif }; @@ -116,10 +116,10 @@ void TopologicalSortMethod::sortPrimitives(vector& primitive_tab,V #ifdef DEBUG_TS cout << "Computing precedence graph." << endl ; cout << "Old order: " ; - for(unsigned int i=0;i > precedence_graph(primitive_tab.size()); + vector< vector > precedence_graph(primitive_tab.size()); TopologicalSortUtils::buildPrecedenceGraph(primitive_tab,precedence_graph) ; #ifdef DEBUG_TS @@ -138,19 +138,19 @@ void TopologicalSortMethod::sortPrimitives(vector& primitive_tab,V #ifdef DEBUG_TS cout << "New order: " ; - for(unsigned int i=0;i >& precedence_graph, +void TopologicalSortUtils::printPrecedenceGraph(const vector< vector >& precedence_graph, const vector& primitive_tab) { - for(unsigned int i=0;inbVertices() << ") : " ; - for(unsigned int j=0;j >& pre #endif void TopologicalSortUtils::buildPrecedenceGraph(vector& primitive_tab, - vector< vector >& precedence_graph) + vector< vector >& precedence_graph) { // The precedence graph is constructed by first conservatively determining which // primitives can possibly intersect using a quadtree. Candidate pairs of @@ -173,7 +173,7 @@ void TopologicalSortUtils::buildPrecedenceGraph(vector& primitive_ AxisAlignedBox_xy BBox ; - for(unsigned int i=0;ibbox().mini().x(),primitive_tab[i]->bbox().mini().y())) ; BBox.include(Vector2(primitive_tab[i]->bbox().maxi().x(),primitive_tab[i]->bbox().maxi().y())) ; @@ -181,30 +181,30 @@ void TopologicalSortUtils::buildPrecedenceGraph(vector& primitive_ // 1 - recursively find pairs. - vector pindices(primitive_tab.size()) ; - for(unsigned int j=0;j pindices(primitive_tab.size()) ; + for(size_t j=0;j& primitive_tab, - const vector& pindices, - vector< vector >& precedence_graph, + const vector& pindices, + vector< vector >& precedence_graph, const AxisAlignedBox_xy& bbox, int depth) { - static const unsigned int MAX_PRIMITIVES_IN_CELL = 5 ; + static const size_t MAX_PRIMITIVES_IN_CELL = 5 ; // Refinment: first decide which sub-cell each primitive meets, then call // algorithm recursively. if(primitive_tab.size() > MAX_PRIMITIVES_IN_CELL) { - vector p_indices_min_min ; - vector p_indices_min_max ; - vector p_indices_max_min ; - vector p_indices_max_max ; + vector p_indices_min_min ; + vector p_indices_min_max ; + vector p_indices_max_min ; + vector p_indices_max_max ; double xmin = bbox.mini().x() ; double ymin = bbox.mini().y() ; @@ -214,7 +214,7 @@ void TopologicalSortUtils::recursFindNeighbors(const vector& primi double xMean = 0.5*(xmin+xmax) ; double yMean = 0.5*(ymin+ymax) ; - for(unsigned int i=0;ibbox().mini().x() <= xMean ; bool right = primitive_tab[pindices[i]]->bbox().maxi().x() >= xMean ; @@ -243,8 +243,8 @@ void TopologicalSortUtils::recursFindNeighbors(const vector& primi // No refinment either because it could not be possible, or because the number of primitives is below // the predefined limit. - for(unsigned int i=0;i& primi } } -void TopologicalSortUtils::checkAndAddEdgeToGraph(int a,int b,vector< vector >& precedence_graph) +void TopologicalSortUtils::checkAndAddEdgeToGraph(size_t a,size_t b,vector< vector >& precedence_graph) { #ifdef DEBUG_TS cout << "Trying to add " << a << " -> " << b << " " ; #endif bool found = false ; - for(unsigned int k=0;k >& precedence_graph) +void TopologicalSortUtils::suppressPrecedence(size_t a,size_t b,vector< vector >& precedence_graph) { - vector prec_tab = vector(precedence_graph[a]) ; + vector prec_tab = vector(precedence_graph[a]) ; bool trouve = false ; - for(unsigned int k=0;k >& throw runtime_error("Unexpected error in suppressPrecedence") ; } -void TopologicalSortUtils::topologicalSort(vector< vector >& precedence_graph, +void TopologicalSortUtils::topologicalSort(vector< vector >& precedence_graph, vector& primitive_tab, VRenderParams& vparams) { vector new_pr_tab ; vector already_visited(primitive_tab.size(),false) ; vector already_rendered(primitive_tab.size(),false) ; - int nb_skews = 0 ; + size_t nb_skews = 0 ; - unsigned int info_cnt = primitive_tab.size()/200 + 1 ; - int nbrendered = 0 ; + size_t info_cnt = primitive_tab.size()/200 + 1 ; + size_t nbrendered = 0 ; // 1 - sorts primitives by rendering order - for(unsigned int i=0;i >& precedence_gra primitive_tab = new_pr_tab ; } -void TopologicalSortUtils::topologicalSortBreakCycles(vector< vector >& precedence_graph, +void TopologicalSortUtils::topologicalSortBreakCycles(vector< vector >& precedence_graph, vector& primitive_tab, VRenderParams& vparams) { vector new_pr_tab ; vector already_visited(primitive_tab.size(),false) ; vector already_rendered(primitive_tab.size(),false) ; - vector ancestors ; - int nb_skews = 0 ; - int ancestors_backward_index ; + vector ancestors ; + size_t nb_skews = 0 ; + size_t ancestors_backward_index ; - int info_cnt = primitive_tab.size()/200 + 1 ; - int nbrendered = 0 ; + size_t info_cnt = primitive_tab.size()/200 + 1 ; + size_t nbrendered = 0 ; // 1 - sorts primitives by rendering order - for(unsigned int i=0;i >& pre primitive_tab = new_pr_tab ; } -void TopologicalSortUtils::recursTopologicalSort( vector< vector >& precedence_graph, +void TopologicalSortUtils::recursTopologicalSort( vector< vector >& precedence_graph, vector& primitive_tab, vector& already_rendered, vector& already_visited, vector& new_pr_tab, - int indx, - int& nb_cycles, + size_t indx, + size_t& nb_cycles, VRenderParams& vparams, - int info_cnt,int& nbrendered) + size_t info_cnt,size_t& nbrendered) { // One must first render the primitives indicated by the precedence graph, // then render the current primitive. Skews are detected, but and treated. already_visited[indx] = true ; - for(unsigned int j=0;j >& precede already_visited[indx] = false ; } -void TopologicalSortUtils::recursTopologicalSort( vector< vector >& precedence_graph, +void TopologicalSortUtils::recursTopologicalSort( vector< vector >& precedence_graph, vector& primitive_tab, vector& already_rendered, vector& already_visited, vector& new_pr_tab, - int indx, - vector& ancestors, - int& ancestors_backward_index, - int& nb_cycles, + size_t indx, + vector& ancestors, + size_t& ancestors_backward_index, + size_t& nb_cycles, VRenderParams& vparams, - int info_cnt,int& nbrendered) + size_t info_cnt,size_t& nbrendered) { // One must first render the primitives indicated by the precedence graph, // then render the current primitive. Skews are detected, but and treated. @@ -410,7 +410,7 @@ void TopologicalSortUtils::recursTopologicalSort( vector< vector >& precede already_visited[indx] = true ; ancestors.push_back(indx) ; - for(unsigned int j=0;j >& precede recursTopologicalSort( precedence_graph,primitive_tab,already_rendered,already_visited, new_pr_tab,precedence_graph[indx][j],ancestors,ancestors_backward_index,nb_cycles,vparams,info_cnt,nbrendered) ; - if(ancestors_backward_index != INT_MAX && ancestors.size() > (unsigned int)(ancestors_backward_index+1)) + if(ancestors_backward_index != INT_MAX && ancestors.size() > (size_t)(ancestors_backward_index+1)) { #ifdef DEBUG_TS cout << "Returning early" << endl ; @@ -449,13 +449,13 @@ void TopologicalSortUtils::recursTopologicalSort( vector< vector >& precede // 0.5 - determine cycle beginning - int cycle_beginning_index = -1 ; - for(int i=(int)(ancestors.size())-1; i >= 0 && cycle_beginning_index < 0;--i) + long cycle_beginning_index = -1 ; + for(size_t i=ancestors.size()-1; long(i) >= 0 && cycle_beginning_index < 0;--i) if(ancestors[i] == precedence_graph[indx][j]) - cycle_beginning_index = i ; + cycle_beginning_index = (long)i ; #ifdef DEBUG_TS cout << "Unbreaking cycle : " ; - for(unsigned int i=0;i >& precede #endif // 1 - determine splitting plane - int split_prim_ancestor_indx = -1 ; - int split_prim_indx = -1 ; + long split_prim_ancestor_indx = -1 ; + long split_prim_indx = -1 ; // Go down ancestors tab, starting from the skewing primitive, and stopping at it. - for(unsigned int i2=cycle_beginning_index;i2nbVertices() > 2) { - split_prim_ancestor_indx = i2 ; - split_prim_indx = ancestors[i2] ; + split_prim_ancestor_indx = (long)i2 ; + split_prim_indx = (long)ancestors[i2] ; } #ifdef DEBUG_TS @@ -484,15 +484,15 @@ void TopologicalSortUtils::recursTopologicalSort( vector< vector >& precede // 2 - split all necessary primitives - const Polygone *P = dynamic_cast(primitive_tab[split_prim_indx]) ; + const Polygone *P = dynamic_cast(primitive_tab[(size_t)split_prim_indx]) ; const NVector3& normal = NVector3(P->normal()) ; double c(P->c()) ; ancestors.push_back(precedence_graph[indx][j]) ; // sentinel - ancestors.push_back(ancestors[cycle_beginning_index+1]) ; // sentinel + ancestors.push_back(ancestors[(size_t)cycle_beginning_index+1]) ; // sentinel bool cycle_broken = false ; - for(unsigned int i3=cycle_beginning_index+1;i3 >& precede cout << "Splitted primitive " << ancestors[i3] << endl ; #endif - vector prim_upper_prec ; - vector prim_lower_prec ; + vector prim_upper_prec ; + vector prim_lower_prec ; - vector old_prec = vector(precedence_graph[ancestors[i3]]) ; + vector old_prec = vector(precedence_graph[ancestors[i3]]) ; - unsigned int upper_indx = precedence_graph.size() ; - int lower_indx = ancestors[i3] ; + size_t upper_indx = precedence_graph.size() ; + size_t lower_indx = ancestors[i3] ; // Updates the precedence graph downwards. - for(unsigned int k=0;k >& precede // dual precedence graph. For now it's O(n^2). This test can not // be skipped because upper can still be lower to ancestors[i-1]. - for(unsigned int l=0;l >& precede precedence_graph[l].push_back(upper_indx) ; - if(l == (unsigned int)ancestors[i3-1]) + if(l == (size_t)ancestors[i3-1]) prim_upper_ante_contains_im1 = true ; } // If the primitive is not upper anymore there is @@ -601,7 +601,7 @@ void TopologicalSortUtils::recursTopologicalSort( vector< vector >& precede #ifdef DEBUG_TS cout << " > " << endl ; #endif - if(l == (unsigned int)ancestors[i3-1]) // The index is the same => nothing to change. + if(l == (size_t)ancestors[i3-1]) // The index is the same => nothing to change. prim_lower_ante_contains_im1 = true ; } else @@ -654,7 +654,7 @@ void TopologicalSortUtils::recursTopologicalSort( vector< vector >& precede if(cycle_broken) { - ancestors_backward_index = cycle_beginning_index ; + ancestors_backward_index = (size_t)cycle_beginning_index ; #ifdef DEBUG_TS cout << "Cycle broken. Jumping back to rank " << ancestors_backward_index << endl ; #endif diff --git a/octovis/src/extern/QGLViewer/VRender/Types.h b/octovis/src/extern/QGLViewer/VRender/Types.h index 3f9d16bd..e7c0944e 100644 --- a/octovis/src/extern/QGLViewer/VRender/Types.h +++ b/octovis/src/extern/QGLViewer/VRender/Types.h @@ -22,9 +22,9 @@ /**************************************************************************** - Copyright (C) 2002-2013 Gilles Debunne. All rights reserved. + Copyright (C) 2002-2014 Gilles Debunne. All rights reserved. - This file is part of the QGLViewer library version 2.4.0. + This file is part of the QGLViewer library version 2.6.3. http://www.libqglviewer.com - contact@libqglviewer.com diff --git a/octovis/src/extern/QGLViewer/VRender/VRender.cpp b/octovis/src/extern/QGLViewer/VRender/VRender.cpp index 26036115..60562fe1 100644 --- a/octovis/src/extern/QGLViewer/VRender/VRender.cpp +++ b/octovis/src/extern/QGLViewer/VRender/VRender.cpp @@ -22,9 +22,9 @@ /**************************************************************************** - Copyright (C) 2002-2013 Gilles Debunne. All rights reserved. + Copyright (C) 2002-2014 Gilles Debunne. All rights reserved. - This file is part of the QGLViewer library version 2.4.0. + This file is part of the QGLViewer library version 2.6.3. http://www.libqglviewer.com - contact@libqglviewer.com diff --git a/octovis/src/extern/QGLViewer/VRender/VRender.h b/octovis/src/extern/QGLViewer/VRender/VRender.h index 79ca156d..5235fe82 100644 --- a/octovis/src/extern/QGLViewer/VRender/VRender.h +++ b/octovis/src/extern/QGLViewer/VRender/VRender.h @@ -22,9 +22,9 @@ /**************************************************************************** - Copyright (C) 2002-2013 Gilles Debunne. All rights reserved. + Copyright (C) 2002-2014 Gilles Debunne. All rights reserved. - This file is part of the QGLViewer library version 2.4.0. + This file is part of the QGLViewer library version 2.6.3. http://www.libqglviewer.com - contact@libqglviewer.com @@ -46,13 +46,8 @@ #define _VRENDER_H_ #include "../config.h" -#if QT_VERSION >= 0x040000 -# include -# include -#else -# include -# include -#endif +#include +#include #include "../qglviewer.h" diff --git a/octovis/src/extern/QGLViewer/VRender/Vector2.cpp b/octovis/src/extern/QGLViewer/VRender/Vector2.cpp index 14aba5a2..2748b5bc 100644 --- a/octovis/src/extern/QGLViewer/VRender/Vector2.cpp +++ b/octovis/src/extern/QGLViewer/VRender/Vector2.cpp @@ -22,9 +22,9 @@ /**************************************************************************** - Copyright (C) 2002-2013 Gilles Debunne. All rights reserved. + Copyright (C) 2002-2014 Gilles Debunne. All rights reserved. - This file is part of the QGLViewer library version 2.4.0. + This file is part of the QGLViewer library version 2.6.3. http://www.libqglviewer.com - contact@libqglviewer.com @@ -45,6 +45,7 @@ #include "Vector2.h" #include "Vector3.h" #include +#include #ifdef WIN32 # include @@ -136,11 +137,11 @@ std::ostream& operator<< (std::ostream& out,const Vector2& u) Vector2 Vector2::mini(const Vector2& v1,const Vector2& v2) { - return Vector2(min(v1[0],v2[0]),min(v1[1],v2[1])) ; + return Vector2(std::min(v1[0],v2[0]),std::min(v1[1],v2[1])) ; } Vector2 Vector2::maxi(const Vector2& v1,const Vector2& v2) { - return Vector2(max(v1[0],v2[0]),max(v1[1],v2[1])) ; + return Vector2(std::max(v1[0],v2[0]),std::max(v1[1],v2[1])) ; } diff --git a/octovis/src/extern/QGLViewer/VRender/Vector2.h b/octovis/src/extern/QGLViewer/VRender/Vector2.h index fd97d7ad..9414768e 100644 --- a/octovis/src/extern/QGLViewer/VRender/Vector2.h +++ b/octovis/src/extern/QGLViewer/VRender/Vector2.h @@ -22,9 +22,9 @@ /**************************************************************************** - Copyright (C) 2002-2013 Gilles Debunne. All rights reserved. + Copyright (C) 2002-2014 Gilles Debunne. All rights reserved. - This file is part of the QGLViewer library version 2.4.0. + This file is part of the QGLViewer library version 2.6.3. http://www.libqglviewer.com - contact@libqglviewer.com diff --git a/octovis/src/extern/QGLViewer/VRender/Vector3.cpp b/octovis/src/extern/QGLViewer/VRender/Vector3.cpp index c629370f..1292f5d8 100644 --- a/octovis/src/extern/QGLViewer/VRender/Vector3.cpp +++ b/octovis/src/extern/QGLViewer/VRender/Vector3.cpp @@ -22,9 +22,9 @@ /**************************************************************************** - Copyright (C) 2002-2013 Gilles Debunne. All rights reserved. + Copyright (C) 2002-2014 Gilles Debunne. All rights reserved. - This file is part of the QGLViewer library version 2.4.0. + This file is part of the QGLViewer library version 2.6.3. http://www.libqglviewer.com - contact@libqglviewer.com @@ -46,6 +46,7 @@ #include "Vector3.h" #include "NVector3.h" #include +#include #ifdef WIN32 # include @@ -145,7 +146,7 @@ double Vector3::squareNorm () const //! Infinite norm double Vector3::infNorm() const { - return max(max(fabs(_xyz[0]),fabs(_xyz[1])),fabs(_xyz[2])) ; + return std::max(std::max(fabs(_xyz[0]),fabs(_xyz[1])),fabs(_xyz[2])) ; } @@ -159,11 +160,11 @@ std::ostream& vrender::operator<< (std::ostream& out,const Vector3& u) Vector3 Vector3::mini(const Vector3& v1,const Vector3& v2) { - return Vector3(min(v1[0],v2[0]),min(v1[1],v2[1]),min(v1[2],v2[2])) ; + return Vector3(std::min(v1[0],v2[0]),std::min(v1[1],v2[1]),std::min(v1[2],v2[2])) ; } Vector3 Vector3::maxi(const Vector3& v1,const Vector3& v2) { - return Vector3(max(v1[0],v2[0]),max(v1[1],v2[1]),max(v1[2],v2[2])) ; + return Vector3(std::max(v1[0],v2[0]),std::max(v1[1],v2[1]),std::max(v1[2],v2[2])) ; } diff --git a/octovis/src/extern/QGLViewer/VRender/Vector3.h b/octovis/src/extern/QGLViewer/VRender/Vector3.h index 5935ce5b..f6a58535 100644 --- a/octovis/src/extern/QGLViewer/VRender/Vector3.h +++ b/octovis/src/extern/QGLViewer/VRender/Vector3.h @@ -22,9 +22,9 @@ /**************************************************************************** - Copyright (C) 2002-2013 Gilles Debunne. All rights reserved. + Copyright (C) 2002-2014 Gilles Debunne. All rights reserved. - This file is part of the QGLViewer library version 2.4.0. + This file is part of the QGLViewer library version 2.6.3. http://www.libqglviewer.com - contact@libqglviewer.com diff --git a/octovis/src/extern/QGLViewer/VRender/VisibilityOptimizer.cpp b/octovis/src/extern/QGLViewer/VRender/VisibilityOptimizer.cpp index 9c3d7353..62271b74 100644 --- a/octovis/src/extern/QGLViewer/VRender/VisibilityOptimizer.cpp +++ b/octovis/src/extern/QGLViewer/VRender/VisibilityOptimizer.cpp @@ -22,9 +22,9 @@ /**************************************************************************** - Copyright (C) 2002-2013 Gilles Debunne. All rights reserved. + Copyright (C) 2002-2014 Gilles Debunne. All rights reserved. - This file is part of the QGLViewer library version 2.4.0. + This file is part of the QGLViewer library version 2.6.3. http://www.libqglviewer.com - contact@libqglviewer.com @@ -61,7 +61,7 @@ void VisibilityOptimizer::optimize(vector& primitives,VRenderParam #ifdef DEBUG_VO cout << "Optimizing visibility." << endl ; #endif - unsigned int N = primitives.size()/200 + 1 ; + unsigned long N = primitives.size()/200 + 1 ; #ifdef DEBUG_EPSRENDER__SHOW1 // cout << "Showing viewer." << endl ; @@ -99,9 +99,9 @@ void VisibilityOptimizer::optimize(vector& primitives,VRenderParam cumulated_union.num_contours = 0 ; cumulated_union.hole = NULL ; cumulated_union.contour = NULL ; - int nboptimised = 0 ; + size_t nboptimised = 0 ; - for(int pindex = (int)(primitives.size()) - 1; pindex >= 0;--pindex,++nboptimised) + for(size_t pindex = primitives.size() - 1; long(pindex) >= 0;--pindex,++nboptimised) if(primitives[pindex] != NULL) { #ifdef A_FAIRE @@ -114,7 +114,7 @@ void VisibilityOptimizer::optimize(vector& primitives,VRenderParam if(pindex%50==0) { char buff[500] ; - sprintf(buff,"Left: % 6ld - Culled: % 6ld", (long)pindex,(long)nb_culled) ; + sprintf(buff,"Left: % 6ld - Culled: % 6ld", pindex,(long)nb_culled) ; fprintf(stdout,buff); for(unsigned int j=0;j& primitives,VRenderParam new_poly_verts->num_vertices = p->nbVertices() ; new_poly_verts->vertex = new gpc_vertex[p->nbVertices()] ; - for(unsigned int i=0;inbVertices();++i) + for(size_t i=0;inbVertices();++i) { new_poly_verts->vertex[i].x = p->vertex(i).x() ; new_poly_verts->vertex[i].y = p->vertex(i).y() ; @@ -194,7 +194,7 @@ void VisibilityOptimizer::optimize(vector& primitives,VRenderParam new_poly_reduced_verts->num_vertices = p->nbVertices() ; new_poly_reduced_verts->vertex = new gpc_vertex[p->nbVertices()] ; - for(unsigned int j=0;jnbVertices();++j) + for(size_t j=0;jnbVertices();++j) { new_poly_reduced_verts->vertex[j].x = mx + (p->vertex(j).x() - mx)*0.999 ; new_poly_reduced_verts->vertex[j].y = my + (p->vertex(j).y() - my)*0.999 ; @@ -243,10 +243,10 @@ void VisibilityOptimizer::optimize(vector& primitives,VRenderParam glColor3f(1.0,0.0,0.0) ; - for(int i=0;i= v[i].vertex.y) \ - && (v[NEXT_INDEX(i, n)].vertex.y > v[i].vertex.y)) + && (v[NEXT_INDEX(i, n)].vertex.y > v[i].vertex.y)) #define NOT_FMAX(v, i, n) (v[NEXT_INDEX(i, n)].vertex.y > v[i].vertex.y) #define REV_MIN(v, i, n) ((v[PREV_INDEX(i, n)].vertex.y > v[i].vertex.y) \ - && (v[NEXT_INDEX(i, n)].vertex.y >= v[i].vertex.y)) + && (v[NEXT_INDEX(i, n)].vertex.y >= v[i].vertex.y)) #define NOT_RMAX(v, i, n) (v[PREV_INDEX(i, n)].vertex.y > v[i].vertex.y) #define VERTEX(e,p,s,x,y) {add_vertex(&((e)->outp[(p)]->v[(s)]), x, y); \ - (e)->outp[(p)]->active++;} + (e)->outp[(p)]->active++;} #define P_EDGE(d,e,p,i,j) {(d)= (e); \ - do {(d)= (d)->prev;} while (!(d)->outp[(p)]); \ - (i)= (d)->bot.x + (d)->dx * ((j)-(d)->bot.y);} + do {(d)= (d)->prev;} while (!(d)->outp[(p)]); \ + (i)= (d)->bot.x + (d)->dx * ((j)-(d)->bot.y);} #define N_EDGE(d,e,p,i,j) {(d)= (e); \ - do {(d)= (d)->next;} while (!(d)->outp[(p)]); \ - (i)= (d)->bot.x + (d)->dx * ((j)-(d)->bot.y);} + do {(d)= (d)->next;} while (!(d)->outp[(p)]); \ + (i)= (d)->bot.x + (d)->dx * ((j)-(d)->bot.y);} #define MALLOC(p, b, s, t) {if ((b) > 0) { \ - p= (t*)malloc(b); if (!(p)) { \ - fprintf(stderr, "gpc malloc failure: %s\n", s); \ - exit(0);}} else p= NULL;} + p= (t*)malloc(b); if (!(p)) { \ + fprintf(stderr, "gpc malloc failure: %s\n", s); \ + exit(0);}} else p= NULL;} #define FREE(p) {if (p) {free(p); (p)= NULL;}} /* =========================================================================== - Private Data Types + Private Data Types =========================================================================== */ @@ -284,7 +284,7 @@ typedef struct bbox_shape /* Contour axis-aligned bounding box */ /* =========================================================================== - Global Data + Global Data =========================================================================== */ @@ -301,7 +301,7 @@ const h_state next_h_state[3][6]= /* =========================================================================== - Private Functions + Private Functions =========================================================================== */ @@ -311,9 +311,9 @@ static void reset_it(it_node **it) while (*it) { - itn= (*it)->next; - FREE(*it); - *it= itn; + itn= (*it)->next; + FREE(*it); + *it= itn; } } @@ -324,9 +324,9 @@ static void reset_lmt(lmt_node **lmt) while (*lmt) { - lmtn= (*lmt)->next; - FREE(*lmt); - *lmt= lmtn; + lmtn= (*lmt)->next; + FREE(*lmt); + *lmt= lmtn; } } @@ -337,43 +337,43 @@ static void insert_bound(edge_node **b, edge_node *e) if (!*b) { - /* Link node e to the tail of the list */ - *b= e; + /* Link node e to the tail of the list */ + *b= e; } else { - /* Do primary sort on the x field */ - if (e[0].bot.x < (*b)[0].bot.x) - { - /* Insert a new node mid-list */ - existing_bound= *b; - *b= e; - (*b)->next_bound= existing_bound; - } - else - { - if (e[0].bot.x == (*b)[0].bot.x) - { - /* Do secondary sort on the dx field */ - if (e[0].dx < (*b)[0].dx) - { - /* Insert a new node mid-list */ - existing_bound= *b; - *b= e; - (*b)->next_bound= existing_bound; - } - else - { - /* Head further down the list */ - insert_bound(&((*b)->next_bound), e); - } - } - else - { - /* Head further down the list */ - insert_bound(&((*b)->next_bound), e); - } - } + /* Do primary sort on the x field */ + if (e[0].bot.x < (*b)[0].bot.x) + { + /* Insert a new node mid-list */ + existing_bound= *b; + *b= e; + (*b)->next_bound= existing_bound; + } + else + { + if (e[0].bot.x == (*b)[0].bot.x) + { + /* Do secondary sort on the dx field */ + if (e[0].dx < (*b)[0].dx) + { + /* Insert a new node mid-list */ + existing_bound= *b; + *b= e; + (*b)->next_bound= existing_bound; + } + else + { + /* Head further down the list */ + insert_bound(&((*b)->next_bound), e); + } + } + else + { + /* Head further down the list */ + insert_bound(&((*b)->next_bound), e); + } + } } } @@ -384,31 +384,31 @@ static edge_node **bound_list(lmt_node **lmt, double y) if (!*lmt) { - /* Add node onto the tail end of the LMT */ - MALLOC(*lmt, sizeof(lmt_node), "LMT insertion", lmt_node); - (*lmt)->y= y; - (*lmt)->first_bound= NULL; - (*lmt)->next= NULL; - return &((*lmt)->first_bound); + /* Add node onto the tail end of the LMT */ + MALLOC(*lmt, sizeof(lmt_node), "LMT insertion", lmt_node); + (*lmt)->y= y; + (*lmt)->first_bound= NULL; + (*lmt)->next= NULL; + return &((*lmt)->first_bound); } else - if (y < (*lmt)->y) - { - /* Insert a new LMT node before the current node */ - existing_node= *lmt; - MALLOC(*lmt, sizeof(lmt_node), "LMT insertion", lmt_node); - (*lmt)->y= y; - (*lmt)->first_bound= NULL; - (*lmt)->next= existing_node; - return &((*lmt)->first_bound); - } - else - if (y > (*lmt)->y) - /* Head further up the LMT */ - return bound_list(&((*lmt)->next), y); - else - /* Use this existing LMT node */ - return &((*lmt)->first_bound); + if (y < (*lmt)->y) + { + /* Insert a new LMT node before the current node */ + existing_node= *lmt; + MALLOC(*lmt, sizeof(lmt_node), "LMT insertion", lmt_node); + (*lmt)->y= y; + (*lmt)->first_bound= NULL; + (*lmt)->next= existing_node; + return &((*lmt)->first_bound); + } + else + if (y > (*lmt)->y) + /* Head further up the LMT */ + return bound_list(&((*lmt)->next), y); + else + /* Use this existing LMT node */ + return &((*lmt)->first_bound); } @@ -416,28 +416,28 @@ static void add_to_sbtree(int *entries, sb_tree **sbtree, double y) { if (!*sbtree) { - /* Add a new tree node here */ - MALLOC(*sbtree, sizeof(sb_tree), "scanbeam tree insertion", sb_tree); - (*sbtree)->y= y; - (*sbtree)->less= NULL; - (*sbtree)->more= NULL; - (*entries)++; + /* Add a new tree node here */ + MALLOC(*sbtree, sizeof(sb_tree), "scanbeam tree insertion", sb_tree); + (*sbtree)->y= y; + (*sbtree)->less= NULL; + (*sbtree)->more= NULL; + (*entries)++; } else { - if ((*sbtree)->y > y) - { - /* Head into the 'less' sub-tree */ - add_to_sbtree(entries, &((*sbtree)->less), y); - } - else - { - if ((*sbtree)->y < y) - { - /* Head into the 'more' sub-tree */ - add_to_sbtree(entries, &((*sbtree)->more), y); - } - } + if ((*sbtree)->y > y) + { + /* Head into the 'less' sub-tree */ + add_to_sbtree(entries, &((*sbtree)->less), y); + } + else + { + if ((*sbtree)->y < y) + { + /* Head into the 'more' sub-tree */ + add_to_sbtree(entries, &((*sbtree)->more), y); + } + } } } @@ -445,11 +445,11 @@ static void add_to_sbtree(int *entries, sb_tree **sbtree, double y) static void build_sbt(int *entries, double *sbt, sb_tree *sbtree) { if (sbtree->less) - build_sbt(entries, sbt, sbtree->less); + build_sbt(entries, sbt, sbtree->less); sbt[*entries]= sbtree->y; (*entries)++; if (sbtree->more) - build_sbt(entries, sbt, sbtree->more); + build_sbt(entries, sbt, sbtree->more); } @@ -457,169 +457,169 @@ static void free_sbtree(sb_tree **sbtree) { if (*sbtree) { - free_sbtree(&((*sbtree)->less)); - free_sbtree(&((*sbtree)->more)); - FREE(*sbtree); + free_sbtree(&((*sbtree)->less)); + free_sbtree(&((*sbtree)->more)); + FREE(*sbtree); } } static int count_optimal_vertices(gpc_vertex_list c) { - int result= 0, i; + int result= 0; /* Ignore non-contributing contours */ if (c.num_vertices > 0) { - for (i= 0; i < c.num_vertices; i++) - /* Ignore superfluous vertices embedded in horizontal edges */ - if (OPTIMAL(c.vertex, i, c.num_vertices)) - result++; + for (long i= 0; i < c.num_vertices; i++) + /* Ignore superfluous vertices embedded in horizontal edges */ + if (OPTIMAL(c.vertex, i, c.num_vertices)) + result++; } return result; } static edge_node *build_lmt(lmt_node **lmt, sb_tree **sbtree, - int *sbt_entries, gpc_polygon *p, int type, - gpc_op op) + int *sbt_entries, gpc_polygon *p, int type, + gpc_op op) { - int c, i, min, max, num_edges, v, num_vertices; + int i, min, max, num_edges, v, num_vertices; int total_vertices= 0, e_index=0; edge_node *e, *edge_table; - for (c= 0; c < p->num_contours; c++) - total_vertices+= count_optimal_vertices(p->contour[c]); + for (size_t c= 0; c < p->num_contours; c++) + total_vertices+= count_optimal_vertices(p->contour[c]); /* Create the entire input polygon edge table in one go */ MALLOC(edge_table, total_vertices * sizeof(edge_node), "edge table creation", edge_node); for(int k=0;knum_contours; c++) + for (size_t c= 0; c < p->num_contours; c++) { - if (p->contour[c].num_vertices < 0) - { - /* Ignore the non-contributing contour and repair the vertex count */ - p->contour[c].num_vertices= -p->contour[c].num_vertices; - } - else - { - /* Perform contour optimisation */ - num_vertices= 0; - for (i= 0; i < p->contour[c].num_vertices; i++) - if (OPTIMAL(p->contour[c].vertex, i, p->contour[c].num_vertices)) - { - edge_table[num_vertices].vertex.x= p->contour[c].vertex[i].x; - edge_table[num_vertices].vertex.y= p->contour[c].vertex[i].y; - - /* Record vertex in the scanbeam table */ - add_to_sbtree(sbt_entries, sbtree, - edge_table[num_vertices].vertex.y); - - num_vertices++; - } - - /* Do the contour forward pass */ - for (min= 0; min < num_vertices; min++) - { - /* If a forward local minimum... */ - if (FWD_MIN(edge_table, min, num_vertices)) - { - /* Search for the next local maximum... */ - num_edges= 1; - max= NEXT_INDEX(min, num_vertices); - while (NOT_FMAX(edge_table, max, num_vertices)) - { - num_edges++; - max= NEXT_INDEX(max, num_vertices); - } - - /* Build the next edge list */ - e= &edge_table[e_index]; - e_index+= num_edges; - v= min; - e[0].bstate[BELOW]= UNBUNDLED; - e[0].bundle[BELOW][CLIP]= FALSE; - e[0].bundle[BELOW][SUBJ]= FALSE; - for (i= 0; i < num_edges; i++) - { - e[i].xb= edge_table[v].vertex.x; - e[i].bot.x= edge_table[v].vertex.x; - e[i].bot.y= edge_table[v].vertex.y; - - v= NEXT_INDEX(v, num_vertices); - - e[i].top.x= edge_table[v].vertex.x; - e[i].top.y= edge_table[v].vertex.y; - e[i].dx= (edge_table[v].vertex.x - e[i].bot.x) / - (e[i].top.y - e[i].bot.y); - e[i].type= type; - e[i].outp[ABOVE]= NULL; - e[i].outp[BELOW]= NULL; - e[i].next= NULL; - e[i].prev= NULL; - e[i].succ= ((num_edges > 1) && (i < (num_edges - 1))) ? - &(e[i + 1]) : NULL; - e[i].pred= ((num_edges > 1) && (i > 0)) ? &(e[i - 1]) : NULL; - e[i].next_bound= NULL; - e[i].bside[CLIP]= (op == GPC_DIFF) ? RIGHT : LEFT; - e[i].bside[SUBJ]= LEFT; - } - insert_bound(bound_list(lmt, edge_table[min].vertex.y), e); - } - } - - /* Do the contour reverse pass */ - for (min= 0; min < num_vertices; min++) - { - /* If a reverse local minimum... */ - if (REV_MIN(edge_table, min, num_vertices)) - { - /* Search for the previous local maximum... */ - num_edges= 1; - max= PREV_INDEX(min, num_vertices); - while (NOT_RMAX(edge_table, max, num_vertices)) - { - num_edges++; - max= PREV_INDEX(max, num_vertices); - } - - /* Build the previous edge list */ - e= &edge_table[e_index]; - e_index+= num_edges; - v= min; - e[0].bstate[BELOW]= UNBUNDLED; - e[0].bundle[BELOW][CLIP]= FALSE; - e[0].bundle[BELOW][SUBJ]= FALSE; - for (i= 0; i < num_edges; i++) - { - e[i].xb= edge_table[v].vertex.x; - e[i].bot.x= edge_table[v].vertex.x; - e[i].bot.y= edge_table[v].vertex.y; - - v= PREV_INDEX(v, num_vertices); - - e[i].top.x= edge_table[v].vertex.x; - e[i].top.y= edge_table[v].vertex.y; - e[i].dx= (edge_table[v].vertex.x - e[i].bot.x) / - (e[i].top.y - e[i].bot.y); - e[i].type= type; - e[i].outp[ABOVE]= NULL; - e[i].outp[BELOW]= NULL; - e[i].next= NULL; - e[i].prev= NULL; - e[i].succ= ((num_edges > 1) && (i < (num_edges - 1))) ? - &(e[i + 1]) : NULL; - e[i].pred= ((num_edges > 1) && (i > 0)) ? &(e[i - 1]) : NULL; - e[i].next_bound= NULL; - e[i].bside[CLIP]= (op == GPC_DIFF) ? RIGHT : LEFT; - e[i].bside[SUBJ]= LEFT; - } - insert_bound(bound_list(lmt, edge_table[min].vertex.y), e); - } - } - } + if (p->contour[c].num_vertices < 0) + { + /* Ignore the non-contributing contour and repair the vertex count */ + p->contour[c].num_vertices= -p->contour[c].num_vertices; + } + else + { + /* Perform contour optimisation */ + num_vertices= 0; + for (i= 0; i < p->contour[c].num_vertices; i++) + if (OPTIMAL(p->contour[c].vertex, i, p->contour[c].num_vertices)) + { + edge_table[num_vertices].vertex.x= p->contour[c].vertex[i].x; + edge_table[num_vertices].vertex.y= p->contour[c].vertex[i].y; + + /* Record vertex in the scanbeam table */ + add_to_sbtree(sbt_entries, sbtree, + edge_table[num_vertices].vertex.y); + + num_vertices++; + } + + /* Do the contour forward pass */ + for (min= 0; min < num_vertices; min++) + { + /* If a forward local minimum... */ + if (FWD_MIN(edge_table, min, num_vertices)) + { + /* Search for the next local maximum... */ + num_edges= 1; + max= NEXT_INDEX(min, num_vertices); + while (NOT_FMAX(edge_table, max, num_vertices)) + { + num_edges++; + max= NEXT_INDEX(max, num_vertices); + } + + /* Build the next edge list */ + e= &edge_table[e_index]; + e_index+= num_edges; + v= min; + e[0].bstate[BELOW]= UNBUNDLED; + e[0].bundle[BELOW][CLIP]= FALSE; + e[0].bundle[BELOW][SUBJ]= FALSE; + for (i= 0; i < num_edges; i++) + { + e[i].xb= edge_table[v].vertex.x; + e[i].bot.x= edge_table[v].vertex.x; + e[i].bot.y= edge_table[v].vertex.y; + + v= NEXT_INDEX(v, num_vertices); + + e[i].top.x= edge_table[v].vertex.x; + e[i].top.y= edge_table[v].vertex.y; + e[i].dx= (edge_table[v].vertex.x - e[i].bot.x) / + (e[i].top.y - e[i].bot.y); + e[i].type= type; + e[i].outp[ABOVE]= NULL; + e[i].outp[BELOW]= NULL; + e[i].next= NULL; + e[i].prev= NULL; + e[i].succ= ((num_edges > 1) && (i < (num_edges - 1))) ? + &(e[i + 1]) : NULL; + e[i].pred= ((num_edges > 1) && (i > 0)) ? &(e[i - 1]) : NULL; + e[i].next_bound= NULL; + e[i].bside[CLIP]= (op == GPC_DIFF) ? RIGHT : LEFT; + e[i].bside[SUBJ]= LEFT; + } + insert_bound(bound_list(lmt, edge_table[min].vertex.y), e); + } + } + + /* Do the contour reverse pass */ + for (min= 0; min < num_vertices; min++) + { + /* If a reverse local minimum... */ + if (REV_MIN(edge_table, min, num_vertices)) + { + /* Search for the previous local maximum... */ + num_edges= 1; + max= PREV_INDEX(min, num_vertices); + while (NOT_RMAX(edge_table, max, num_vertices)) + { + num_edges++; + max= PREV_INDEX(max, num_vertices); + } + + /* Build the previous edge list */ + e= &edge_table[e_index]; + e_index+= num_edges; + v= min; + e[0].bstate[BELOW]= UNBUNDLED; + e[0].bundle[BELOW][CLIP]= FALSE; + e[0].bundle[BELOW][SUBJ]= FALSE; + for (i= 0; i < num_edges; i++) + { + e[i].xb= edge_table[v].vertex.x; + e[i].bot.x= edge_table[v].vertex.x; + e[i].bot.y= edge_table[v].vertex.y; + + v= PREV_INDEX(v, num_vertices); + + e[i].top.x= edge_table[v].vertex.x; + e[i].top.y= edge_table[v].vertex.y; + e[i].dx= (edge_table[v].vertex.x - e[i].bot.x) / + (e[i].top.y - e[i].bot.y); + e[i].type= type; + e[i].outp[ABOVE]= NULL; + e[i].outp[BELOW]= NULL; + e[i].next= NULL; + e[i].prev= NULL; + e[i].succ= ((num_edges > 1) && (i < (num_edges - 1))) ? + &(e[i + 1]) : NULL; + e[i].pred= ((num_edges > 1) && (i > 0)) ? &(e[i - 1]) : NULL; + e[i].next_bound= NULL; + e[i].bside[CLIP]= (op == GPC_DIFF) ? RIGHT : LEFT; + e[i].bside[SUBJ]= LEFT; + } + insert_bound(bound_list(lmt, edge_table[min].vertex.y), e); + } + } + } } return edge_table; } @@ -629,132 +629,132 @@ static void add_edge_to_aet(edge_node **aet, edge_node *edge, edge_node *prev) { if (!*aet) { - /* Append edge onto the tail end of the AET */ - *aet= edge; - edge->prev= prev; - edge->next= NULL; + /* Append edge onto the tail end of the AET */ + *aet= edge; + edge->prev= prev; + edge->next= NULL; } else { - /* Do primary sort on the xb field */ - if (edge->xb < (*aet)->xb) - { - /* Insert edge here (before the AET edge) */ - edge->prev= prev; - edge->next= *aet; - (*aet)->prev= edge; - *aet= edge; - } - else - { - if (edge->xb == (*aet)->xb) - { - /* Do secondary sort on the dx field */ - if (edge->dx < (*aet)->dx) - { - /* Insert edge here (before the AET edge) */ - edge->prev= prev; - edge->next= *aet; - (*aet)->prev= edge; - *aet= edge; - } - else - { - /* Head further into the AET */ - add_edge_to_aet(&((*aet)->next), edge, *aet); - } - } - else - { - /* Head further into the AET */ - add_edge_to_aet(&((*aet)->next), edge, *aet); - } - } + /* Do primary sort on the xb field */ + if (edge->xb < (*aet)->xb) + { + /* Insert edge here (before the AET edge) */ + edge->prev= prev; + edge->next= *aet; + (*aet)->prev= edge; + *aet= edge; + } + else + { + if (edge->xb == (*aet)->xb) + { + /* Do secondary sort on the dx field */ + if (edge->dx < (*aet)->dx) + { + /* Insert edge here (before the AET edge) */ + edge->prev= prev; + edge->next= *aet; + (*aet)->prev= edge; + *aet= edge; + } + else + { + /* Head further into the AET */ + add_edge_to_aet(&((*aet)->next), edge, *aet); + } + } + else + { + /* Head further into the AET */ + add_edge_to_aet(&((*aet)->next), edge, *aet); + } + } } } static void add_intersection(it_node **it, edge_node *edge0, edge_node *edge1, - double x, double y) + double x, double y) { it_node *existing_node; if (!*it) { - /* Append a new node to the tail of the list */ - MALLOC(*it, sizeof(it_node), "IT insertion", it_node); - (*it)->ie[0]= edge0; - (*it)->ie[1]= edge1; - (*it)->point.x= x; - (*it)->point.y= y; - (*it)->next= NULL; + /* Append a new node to the tail of the list */ + MALLOC(*it, sizeof(it_node), "IT insertion", it_node); + (*it)->ie[0]= edge0; + (*it)->ie[1]= edge1; + (*it)->point.x= x; + (*it)->point.y= y; + (*it)->next= NULL; } else { - if ((*it)->point.y > y) - { - /* Insert a new node mid-list */ - existing_node= *it; - MALLOC(*it, sizeof(it_node), "IT insertion", it_node); - (*it)->ie[0]= edge0; - (*it)->ie[1]= edge1; - (*it)->point.x= x; - (*it)->point.y= y; - (*it)->next= existing_node; - } - else - /* Head further down the list */ - add_intersection(&((*it)->next), edge0, edge1, x, y); + if ((*it)->point.y > y) + { + /* Insert a new node mid-list */ + existing_node= *it; + MALLOC(*it, sizeof(it_node), "IT insertion", it_node); + (*it)->ie[0]= edge0; + (*it)->ie[1]= edge1; + (*it)->point.x= x; + (*it)->point.y= y; + (*it)->next= existing_node; + } + else + /* Head further down the list */ + add_intersection(&((*it)->next), edge0, edge1, x, y); } } static void add_st_edge(st_node **st, it_node **it, edge_node *edge, - double dy) + double dy) { st_node *existing_node; double den, r, x, y; if (!*st) { - /* Append edge onto the tail end of the ST */ - MALLOC(*st, sizeof(st_node), "ST insertion", st_node); - (*st)->edge= edge; - (*st)->xb= edge->xb; - (*st)->xt= edge->xt; - (*st)->dx= edge->dx; - (*st)->prev= NULL; + /* Append edge onto the tail end of the ST */ + MALLOC(*st, sizeof(st_node), "ST insertion", st_node); + (*st)->edge= edge; + (*st)->xb= edge->xb; + (*st)->xt= edge->xt; + (*st)->dx= edge->dx; + (*st)->prev= NULL; } else { - den= ((*st)->xt - (*st)->xb) - (edge->xt - edge->xb); - - /* If new edge and ST edge don't cross */ - if ((edge->xt >= (*st)->xt) || (edge->dx == (*st)->dx) || - (fabs(den) <= DBL_EPSILON)) - { - /* No intersection - insert edge here (before the ST edge) */ - existing_node= *st; - MALLOC(*st, sizeof(st_node), "ST insertion", st_node); - (*st)->edge= edge; - (*st)->xb= edge->xb; - (*st)->xt= edge->xt; - (*st)->dx= edge->dx; - (*st)->prev= existing_node; - } - else - { - /* Compute intersection between new edge and ST edge */ - r= (edge->xb - (*st)->xb) / den; - x= (*st)->xb + r * ((*st)->xt - (*st)->xb); - y= r * dy; - - /* Insert the edge pointers and the intersection point in the IT */ - add_intersection(it, (*st)->edge, edge, x, y); - - /* Head further into the ST */ - add_st_edge(&((*st)->prev), it, edge, dy); - } + den= ((*st)->xt - (*st)->xb) - (edge->xt - edge->xb); + + /* If new edge and ST edge don't cross */ + if ((edge->xt >= (*st)->xt) || (edge->dx == (*st)->dx) || + (fabs(den) <= DBL_EPSILON)) + { + /* No intersection - insert edge here (before the ST edge) */ + existing_node= *st; + MALLOC(*st, sizeof(st_node), "ST insertion", st_node); + (*st)->edge= edge; + (*st)->xb= edge->xb; + (*st)->xt= edge->xt; + (*st)->dx= edge->dx; + (*st)->prev= existing_node; + } + else + { + /* Compute intersection between new edge and ST edge */ + r= (edge->xb - (*st)->xb) / den; + x= (*st)->xb + r * ((*st)->xt - (*st)->xb); + y= r * dy; + + /* Insert the edge pointers and the intersection point in the IT */ + add_intersection(it, (*st)->edge, edge, x, y); + + /* Head further into the ST */ + add_st_edge(&((*st)->prev), it, edge, dy); + } } } @@ -771,17 +771,17 @@ static void build_intersection_table(it_node **it, edge_node *aet, double dy) /* Process each AET edge */ for (edge= aet; edge; edge= edge->next) { - if ((edge->bstate[ABOVE] == BUNDLE_HEAD) || - edge->bundle[ABOVE][CLIP] || edge->bundle[ABOVE][SUBJ]) - add_st_edge(&st, it, edge, dy); + if ((edge->bstate[ABOVE] == BUNDLE_HEAD) || + edge->bundle[ABOVE][CLIP] || edge->bundle[ABOVE][SUBJ]) + add_st_edge(&st, it, edge, dy); } /* Free the sorted edge table */ while (st) { - stp= st->prev; - FREE(st); - st= stp; + stp= st->prev; + FREE(st); + st= stp; } } @@ -791,30 +791,30 @@ static int count_contours(polygon_node *polygon) vertex_node *v, *nextv; for (nc= 0; polygon; polygon= polygon->next) - if (polygon->active) - { - /* Count the vertices in the current contour */ - nv= 0; - for (v= polygon->proxy->v[LEFT]; v; v= v->next) - nv++; - - /* Record valid vertex counts in the active field */ - if (nv > 2) - { - polygon->active= nv; - nc++; - } - else - { - /* Invalid contour: just free the heap */ - for (v= polygon->proxy->v[LEFT]; v; v= nextv) - { - nextv= v->next; - FREE(v); - } - polygon->active= 0; - } - } + if (polygon->active) + { + /* Count the vertices in the current contour */ + nv= 0; + for (v= polygon->proxy->v[LEFT]; v; v= v->next) + nv++; + + /* Record valid vertex counts in the active field */ + if (nv > 2) + { + polygon->active= nv; + nc++; + } + else + { + /* Invalid contour: just free the heap */ + for (v= polygon->proxy->v[LEFT]; v; v= nextv) + { + nextv= v->next; + FREE(v); + } + polygon->active= 0; + } + } return nc; } @@ -850,20 +850,20 @@ static void merge_left(polygon_node *p, polygon_node *q, polygon_node *list) if (p->proxy != q->proxy) { - /* Assign p's vertex list to the left end of q's list */ - p->proxy->v[RIGHT]->next= q->proxy->v[LEFT]; - q->proxy->v[LEFT]= p->proxy->v[LEFT]; - - /* Redirect any p->proxy references to q->proxy */ - - for (target= p->proxy; list; list= list->next) - { - if (list->proxy == target) - { - list->active= FALSE; - list->proxy= q->proxy; - } - } + /* Assign p's vertex list to the left end of q's list */ + p->proxy->v[RIGHT]->next= q->proxy->v[LEFT]; + q->proxy->v[LEFT]= p->proxy->v[LEFT]; + + /* Redirect any p->proxy references to q->proxy */ + + for (target= p->proxy; list; list= list->next) + { + if (list->proxy == target) + { + list->active= FALSE; + list->proxy= q->proxy; + } + } } } @@ -901,25 +901,25 @@ static void merge_right(polygon_node *p, polygon_node *q, polygon_node *list) if (p->proxy != q->proxy) { - /* Assign p's vertex list to the right end of q's list */ - q->proxy->v[RIGHT]->next= p->proxy->v[LEFT]; - q->proxy->v[RIGHT]= p->proxy->v[RIGHT]; - - /* Redirect any p->proxy references to q->proxy */ - for (target= p->proxy; list; list= list->next) - { - if (list->proxy == target) - { - list->active= FALSE; - list->proxy= q->proxy; - } - } + /* Assign p's vertex list to the right end of q's list */ + q->proxy->v[RIGHT]->next= p->proxy->v[LEFT]; + q->proxy->v[RIGHT]= p->proxy->v[RIGHT]; + + /* Redirect any p->proxy references to q->proxy */ + for (target= p->proxy; list; list= list->next) + { + if (list->proxy == target) + { + list->active= FALSE; + list->proxy= q->proxy; + } + } } } static void add_local_min(polygon_node **p, edge_node *edge, - double x, double y) + double x, double y) { polygon_node *existing_min = 0; vertex_node *nv; @@ -956,8 +956,8 @@ static int count_tristrips(polygon_node *tn) int total; for (total= 0; tn; tn= tn->next) - if (tn->active > 2) - total++; + if (tn->active > 2) + total++; return total; } @@ -966,66 +966,66 @@ static void add_vertex(vertex_node **t, double x, double y) { if (!(*t)) { - MALLOC(*t, sizeof(vertex_node), "tristrip vertex creation", vertex_node); - (*t)->x= x; - (*t)->y= y; - (*t)->next= NULL; + MALLOC(*t, sizeof(vertex_node), "tristrip vertex creation", vertex_node); + (*t)->x= x; + (*t)->y= y; + (*t)->next= NULL; } else - /* Head further down the list */ - add_vertex(&((*t)->next), x, y); + /* Head further down the list */ + add_vertex(&((*t)->next), x, y); } static void new_tristrip(polygon_node **tn, edge_node *edge, - double x, double y) + double x, double y) { if (!(*tn)) { - MALLOC(*tn, sizeof(polygon_node), "tristrip node creation", polygon_node); + MALLOC(*tn, sizeof(polygon_node), "tristrip node creation", polygon_node); **tn = polygon_node() ; - (*tn)->next= NULL; - (*tn)->v[LEFT]= NULL; - (*tn)->v[RIGHT]= NULL; - (*tn)->active= 1; - add_vertex(&((*tn)->v[LEFT]), x, y); - edge->outp[ABOVE]= *tn; + (*tn)->next= NULL; + (*tn)->v[LEFT]= NULL; + (*tn)->v[RIGHT]= NULL; + (*tn)->active= 1; + add_vertex(&((*tn)->v[LEFT]), x, y); + edge->outp[ABOVE]= *tn; } else - /* Head further down the list */ - new_tristrip(&((*tn)->next), edge, x, y); + /* Head further down the list */ + new_tristrip(&((*tn)->next), edge, x, y); } static bbox *create_contour_bboxes(gpc_polygon *p) { bbox *box; - int c, v; + int v; MALLOC(box, p->num_contours * sizeof(bbox), "Bounding box creation", bbox); /* Construct contour bounding boxes */ - for (c= 0; c < p->num_contours; c++) + for (size_t c= 0; c < p->num_contours; c++) { - /* Initialise bounding box extent */ - box[c].xmin= DBL_MAX; - box[c].ymin= DBL_MAX; - box[c].xmax= -DBL_MAX; - box[c].ymax= -DBL_MAX; - - for (v= 0; v < p->contour[c].num_vertices; v++) - { - /* Adjust bounding box */ - if (p->contour[c].vertex[v].x < box[c].xmin) - box[c].xmin= p->contour[c].vertex[v].x; - if (p->contour[c].vertex[v].y < box[c].ymin) - box[c].ymin= p->contour[c].vertex[v].y; - if (p->contour[c].vertex[v].x > box[c].xmax) - box[c].xmax= p->contour[c].vertex[v].x; - if (p->contour[c].vertex[v].y > box[c].ymax) - box[c].ymax= p->contour[c].vertex[v].y; - } + /* Initialise bounding box extent */ + box[c].xmin= DBL_MAX; + box[c].ymin= DBL_MAX; + box[c].xmax= -DBL_MAX; + box[c].ymax= -DBL_MAX; + + for (v= 0; v < p->contour[c].num_vertices; v++) + { + /* Adjust bounding box */ + if (p->contour[c].vertex[v].x < box[c].xmin) + box[c].xmin= p->contour[c].vertex[v].x; + if (p->contour[c].vertex[v].y < box[c].ymin) + box[c].ymin= p->contour[c].vertex[v].y; + if (p->contour[c].vertex[v].x > box[c].xmax) + box[c].xmax= p->contour[c].vertex[v].x; + if (p->contour[c].vertex[v].y > box[c].ymax) + box[c].ymax= p->contour[c].vertex[v].y; + } } return box; } @@ -1034,48 +1034,48 @@ static bbox *create_contour_bboxes(gpc_polygon *p) static void minimax_test(gpc_polygon *subj, gpc_polygon *clip, gpc_op op) { bbox *s_bbox, *c_bbox; - int s, c, *o_table, overlap; + int *o_table, overlap; s_bbox= create_contour_bboxes(subj); c_bbox= create_contour_bboxes(clip); MALLOC(o_table, subj->num_contours * clip->num_contours * sizeof(int), - "overlap table creation", int); + "overlap table creation", int); /* Check all subject contour bounding boxes against clip boxes */ - for (s= 0; s < subj->num_contours; s++) - for (c= 0; c < clip->num_contours; c++) - o_table[c * subj->num_contours + s]= - (!((s_bbox[s].xmax < c_bbox[c].xmin) || - (s_bbox[s].xmin > c_bbox[c].xmax))) && - (!((s_bbox[s].ymax < c_bbox[c].ymin) || - (s_bbox[s].ymin > c_bbox[c].ymax))); + for (size_t s= 0; s < subj->num_contours; s++) + for (size_t c= 0; c < clip->num_contours; c++) + o_table[c * subj->num_contours + s]= + (!((s_bbox[s].xmax < c_bbox[c].xmin) || + (s_bbox[s].xmin > c_bbox[c].xmax))) && + (!((s_bbox[s].ymax < c_bbox[c].ymin) || + (s_bbox[s].ymin > c_bbox[c].ymax))); /* For each clip contour, search for any subject contour overlaps */ - for (c= 0; c < clip->num_contours; c++) + for (size_t c= 0; c < clip->num_contours; c++) { - overlap= 0; - for (s= 0; (!overlap) && (s < subj->num_contours); s++) - overlap= o_table[c * subj->num_contours + s]; + overlap= 0; + for (size_t s= 0; (!overlap) && (s < subj->num_contours); s++) + overlap= o_table[c * subj->num_contours + s]; - if (!overlap) - /* Flag non contributing status by negating vertex count */ - clip->contour[c].num_vertices = -clip->contour[c].num_vertices; + if (!overlap) + /* Flag non contributing status by negating vertex count */ + clip->contour[c].num_vertices = -clip->contour[c].num_vertices; } if (op == GPC_INT) { - /* For each subject contour, search for any clip contour overlaps */ - for (s= 0; s < subj->num_contours; s++) - { - overlap= 0; - for (c= 0; (!overlap) && (c < clip->num_contours); c++) - overlap= o_table[c * subj->num_contours + s]; - - if (!overlap) - /* Flag non contributing status by negating vertex count */ - subj->contour[s].num_vertices = -subj->contour[s].num_vertices; - } + /* For each subject contour, search for any clip contour overlaps */ + for (size_t s= 0; s < subj->num_contours; s++) + { + overlap= 0; + for (size_t c= 0; (!overlap) && (c < clip->num_contours); c++) + overlap= o_table[c * subj->num_contours + s]; + + if (!overlap) + /* Flag non contributing status by negating vertex count */ + subj->contour[s].num_vertices = -subj->contour[s].num_vertices; + } } FREE(s_bbox); @@ -1086,16 +1086,14 @@ static void minimax_test(gpc_polygon *subj, gpc_polygon *clip, gpc_op op) /* =========================================================================== - Public Functions + Public Functions =========================================================================== */ void gpc_free_polygon(gpc_polygon *p) { - int c; - - for (c= 0; c < p->num_contours; c++) - FREE(p->contour[c].vertex); + for (size_t c= 0; c < p->num_contours; c++) + FREE(p->contour[c].vertex); FREE(p->hole); FREE(p->contour); p->num_contours= 0; @@ -1108,65 +1106,64 @@ void gpc_read_polygon(FILE *fp, int read_hole_flags, gpc_polygon *p) fscanf(fp, "%d", &(p->num_contours)); MALLOC(p->hole, p->num_contours * sizeof(int), - "hole flag array creation", int); + "hole flag array creation", int); MALLOC(p->contour, p->num_contours - * sizeof(gpc_vertex_list), "contour creation", gpc_vertex_list); + * sizeof(gpc_vertex_list), "contour creation", gpc_vertex_list); for (c= 0; c < p->num_contours; c++) { - fscanf(fp, "%d", &(p->contour[c].num_vertices)); - - if (read_hole_flags) - fscanf(fp, "%d", &(p->hole[c])); - else - p->hole[c]= FALSE; // Assume all contours to be external - - MALLOC(p->contour[c].vertex, p->contour[c].num_vertices - * sizeof(gpc_vertex), "vertex creation", gpc_vertex); - for (v= 0; v < p->contour[c].num_vertices; v++) - fscanf(fp, "%lf %lf", &(p->contour[c].vertex[v].x), - &(p->contour[c].vertex[v].y)); + fscanf(fp, "%d", &(p->contour[c].num_vertices)); + + if (read_hole_flags) + fscanf(fp, "%d", &(p->hole[c])); + else + p->hole[c]= FALSE; // Assume all contours to be external + + MALLOC(p->contour[c].vertex, p->contour[c].num_vertices + * sizeof(gpc_vertex), "vertex creation", gpc_vertex); + for (v= 0; v < p->contour[c].num_vertices; v++) + fscanf(fp, "%lf %lf", &(p->contour[c].vertex[v].x), + &(p->contour[c].vertex[v].y)); } } */ void gpc_write_polygon(FILE *fp, int write_hole_flags, gpc_polygon *p) { - int c, v; - - fprintf(fp, "%d\n", p->num_contours); - for (c= 0; c < p->num_contours; c++) + fprintf(fp, "%lu\n", p->num_contours); + for (size_t c= 0; c < p->num_contours; c++) { - fprintf(fp, "%d\n", p->contour[c].num_vertices); + fprintf(fp, "%lu\n", p->contour[c].num_vertices); - if (write_hole_flags) - fprintf(fp, "%d\n", p->hole[c]); + if (write_hole_flags) + fprintf(fp, "%d\n", p->hole[c]); - for (v= 0; v < p->contour[c].num_vertices; v++) - fprintf(fp, "% .*lf % .*lf\n", - DBL_DIG, p->contour[c].vertex[v].x, - DBL_DIG, p->contour[c].vertex[v].y); + for (long v= 0; v < p->contour[c].num_vertices; v++) + fprintf(fp, "% .*lf % .*lf\n", + DBL_DIG, p->contour[c].vertex[v].x, + DBL_DIG, p->contour[c].vertex[v].y); } } void gpc_add_contour(gpc_polygon *p, gpc_vertex_list *new_contour, int hole) { - int *extended_hole, c, v; + int *extended_hole; + size_t c; gpc_vertex_list *extended_contour; /* Create an extended hole array */ MALLOC(extended_hole, (p->num_contours + 1) - * sizeof(int), "contour hole addition", int); + * sizeof(int), "contour hole addition", int); /* Create an extended contour array */ MALLOC(extended_contour, (p->num_contours + 1) - * sizeof(gpc_vertex_list), "contour addition", gpc_vertex_list); + * sizeof(gpc_vertex_list), "contour addition", gpc_vertex_list); /* Copy the old contour and hole data into the extended arrays */ for (c= 0; c < p->num_contours; c++) { - extended_hole[c]= p->hole[c]; - extended_contour[c]= p->contour[c]; + extended_hole[c]= p->hole[c]; + extended_contour[c]= p->contour[c]; } /* Copy the new contour and hole onto the end of the extended arrays */ @@ -1174,9 +1171,9 @@ void gpc_add_contour(gpc_polygon *p, gpc_vertex_list *new_contour, int hole) extended_hole[c]= hole; extended_contour[c].num_vertices= new_contour->num_vertices; MALLOC(extended_contour[c].vertex, new_contour->num_vertices - * sizeof(gpc_vertex), "contour addition", gpc_vertex); - for (v= 0; v < new_contour->num_vertices; v++) - extended_contour[c].vertex[v]= new_contour->vertex[v]; + * sizeof(gpc_vertex), "contour addition", gpc_vertex); + for (long v= 0; v < new_contour->num_vertices; v++) + extended_contour[c].vertex[v]= new_contour->vertex[v]; /* Dispose of the old contour */ FREE(p->contour); @@ -1190,7 +1187,7 @@ void gpc_add_contour(gpc_polygon *p, gpc_vertex_list *new_contour, int hole) void gpc_polygon_clip(gpc_op op, gpc_polygon *subj, gpc_polygon *clip, - gpc_polygon *result) + gpc_polygon *result) { sb_tree *sbtree= NULL; it_node *it= NULL, *intersect=0; @@ -1210,33 +1207,33 @@ void gpc_polygon_clip(gpc_op op, gpc_polygon *subj, gpc_polygon *clip, || ((subj->num_contours == 0) && ((op == GPC_INT) || (op == GPC_DIFF))) || ((clip->num_contours == 0) && (op == GPC_INT))) { - result->num_contours= 0; - result->hole= NULL; - result->contour= NULL; - return; + result->num_contours= 0; + result->hole= NULL; + result->contour= NULL; + return; } /* Identify potentialy contributing contours */ if (((op == GPC_INT) || (op == GPC_DIFF)) && (subj->num_contours > 0) && (clip->num_contours > 0)) - minimax_test(subj, clip, op); + minimax_test(subj, clip, op); /* Build LMT */ if (subj->num_contours > 0) - s_heap= build_lmt(&lmt, &sbtree, &sbt_entries, subj, SUBJ, op); + s_heap= build_lmt(&lmt, &sbtree, &sbt_entries, subj, SUBJ, op); if (clip->num_contours > 0) - c_heap= build_lmt(&lmt, &sbtree, &sbt_entries, clip, CLIP, op); + c_heap= build_lmt(&lmt, &sbtree, &sbt_entries, clip, CLIP, op); /* Return a NULL result if no contours contribute */ if (lmt == NULL) { - result->num_contours= 0; - result->hole= NULL; - result->contour= NULL; - reset_lmt(&lmt); - FREE(s_heap); - FREE(c_heap); - return; + result->num_contours= 0; + result->hole= NULL; + result->contour= NULL; + reset_lmt(&lmt); + FREE(s_heap); + FREE(c_heap); + return; } /* Build scanbeam table from scanbeam tree */ @@ -1247,531 +1244,531 @@ void gpc_polygon_clip(gpc_op op, gpc_polygon *subj, gpc_polygon *clip, /* Allow pointer re-use without causing memory leak */ if (subj == result) - gpc_free_polygon(subj); + gpc_free_polygon(subj); if (clip == result) - gpc_free_polygon(clip); + gpc_free_polygon(clip); /* Invert clip polygon for difference operation */ if (op == GPC_DIFF) - parity[CLIP]= RIGHT; + parity[CLIP]= RIGHT; local_min= lmt; /* Process each scanbeam */ while (scanbeam < sbt_entries) { - /* Set yb and yt to the bottom and top of the scanbeam */ - yb= sbt[scanbeam++]; - if (scanbeam < sbt_entries) - { - yt= sbt[scanbeam]; - dy= yt - yb; - } - - /* === SCANBEAM BOUNDARY PROCESSING ================================ */ - - /* If LMT node corresponding to yb exists */ - if (local_min) - { - if (local_min->y == yb) - { - /* Add edges starting at this local minimum to the AET */ - for (edge= local_min->first_bound; edge; edge= edge->next_bound) - add_edge_to_aet(&aet, edge, NULL); - - local_min= local_min->next; - } - } - - /* Set dummy previous x value */ - px= -DBL_MAX; - - /* Create bundles within AET */ - e0= aet; - e1= aet; - - /* Set up bundle fields of first edge */ - aet->bundle[ABOVE][ aet->type]= (aet->top.y != yb); - aet->bundle[ABOVE][!aet->type]= FALSE; - aet->bstate[ABOVE]= UNBUNDLED; - - for (next_edge= aet->next; next_edge; next_edge= next_edge->next) - { - /* Set up bundle fields of next edge */ - next_edge->bundle[ABOVE][ next_edge->type]= (next_edge->top.y != yb); - next_edge->bundle[ABOVE][!next_edge->type]= FALSE; - next_edge->bstate[ABOVE]= UNBUNDLED; - - /* Bundle edges above the scanbeam boundary if they coincide */ - if (next_edge->bundle[ABOVE][next_edge->type]) - { - if (EQ(e0->xb, next_edge->xb) && EQ(e0->dx, next_edge->dx) + /* Set yb and yt to the bottom and top of the scanbeam */ + yb= sbt[scanbeam++]; + if (scanbeam < sbt_entries) + { + yt= sbt[scanbeam]; + dy= yt - yb; + } + + /* === SCANBEAM BOUNDARY PROCESSING ================================ */ + + /* If LMT node corresponding to yb exists */ + if (local_min) + { + if (local_min->y == yb) + { + /* Add edges starting at this local minimum to the AET */ + for (edge= local_min->first_bound; edge; edge= edge->next_bound) + add_edge_to_aet(&aet, edge, NULL); + + local_min= local_min->next; + } + } + + /* Set dummy previous x value */ + px= -DBL_MAX; + + /* Create bundles within AET */ + e0= aet; + e1= aet; + + /* Set up bundle fields of first edge */ + aet->bundle[ABOVE][ aet->type]= (aet->top.y != yb); + aet->bundle[ABOVE][!aet->type]= FALSE; + aet->bstate[ABOVE]= UNBUNDLED; + + for (next_edge= aet->next; next_edge; next_edge= next_edge->next) + { + /* Set up bundle fields of next edge */ + next_edge->bundle[ABOVE][ next_edge->type]= (next_edge->top.y != yb); + next_edge->bundle[ABOVE][!next_edge->type]= FALSE; + next_edge->bstate[ABOVE]= UNBUNDLED; + + /* Bundle edges above the scanbeam boundary if they coincide */ + if (next_edge->bundle[ABOVE][next_edge->type]) + { + if (EQ(e0->xb, next_edge->xb) && EQ(e0->dx, next_edge->dx) && (e0->top.y != yb)) - { - next_edge->bundle[ABOVE][ next_edge->type]^= - e0->bundle[ABOVE][ next_edge->type]; - next_edge->bundle[ABOVE][!next_edge->type]= - e0->bundle[ABOVE][!next_edge->type]; - next_edge->bstate[ABOVE]= BUNDLE_HEAD; - e0->bundle[ABOVE][CLIP]= FALSE; - e0->bundle[ABOVE][SUBJ]= FALSE; - e0->bstate[ABOVE]= BUNDLE_TAIL; - } - e0= next_edge; - } - } - - horiz[CLIP]= NH; - horiz[SUBJ]= NH; - - /* Process each edge at this scanbeam boundary */ - for (edge= aet; edge; edge= edge->next) - { - exists[CLIP]= edge->bundle[ABOVE][CLIP] + - (edge->bundle[BELOW][CLIP] << 1); - exists[SUBJ]= edge->bundle[ABOVE][SUBJ] + - (edge->bundle[BELOW][SUBJ] << 1); - - if (exists[CLIP] || exists[SUBJ]) - { - /* Set bundle side */ - edge->bside[CLIP]= parity[CLIP]; - edge->bside[SUBJ]= parity[SUBJ]; - - /* Determine contributing status and quadrant occupancies */ - switch (op) - { - case GPC_DIFF: - case GPC_INT: - contributing= (exists[CLIP] && (parity[SUBJ] || horiz[SUBJ])) - || (exists[SUBJ] && (parity[CLIP] || horiz[CLIP])) - || (exists[CLIP] && exists[SUBJ] - && (parity[CLIP] == parity[SUBJ])); - br= (parity[CLIP]) - && (parity[SUBJ]); - bl= (parity[CLIP] ^ edge->bundle[ABOVE][CLIP]) - && (parity[SUBJ] ^ edge->bundle[ABOVE][SUBJ]); - tr= (parity[CLIP] ^ (horiz[CLIP]!=NH)) - && (parity[SUBJ] ^ (horiz[SUBJ]!=NH)); - tl= (parity[CLIP] ^ (horiz[CLIP]!=NH) ^ edge->bundle[BELOW][CLIP]) - && (parity[SUBJ] ^ (horiz[SUBJ]!=NH) ^ edge->bundle[BELOW][SUBJ]); - break; - case GPC_XOR: - contributing= exists[CLIP] || exists[SUBJ]; - br= (parity[CLIP]) - ^ (parity[SUBJ]); - bl= (parity[CLIP] ^ edge->bundle[ABOVE][CLIP]) - ^ (parity[SUBJ] ^ edge->bundle[ABOVE][SUBJ]); - tr= (parity[CLIP] ^ (horiz[CLIP]!=NH)) - ^ (parity[SUBJ] ^ (horiz[SUBJ]!=NH)); - tl= (parity[CLIP] ^ (horiz[CLIP]!=NH) ^ edge->bundle[BELOW][CLIP]) - ^ (parity[SUBJ] ^ (horiz[SUBJ]!=NH) ^ edge->bundle[BELOW][SUBJ]); - break; - case GPC_UNION: - contributing= (exists[CLIP] && (!parity[SUBJ] || horiz[SUBJ])) - || (exists[SUBJ] && (!parity[CLIP] || horiz[CLIP])) - || (exists[CLIP] && exists[SUBJ] - && (parity[CLIP] == parity[SUBJ])); - br= (parity[CLIP]) - || (parity[SUBJ]); - bl= (parity[CLIP] ^ edge->bundle[ABOVE][CLIP]) - || (parity[SUBJ] ^ edge->bundle[ABOVE][SUBJ]); - tr= (parity[CLIP] ^ (horiz[CLIP]!=NH)) - || (parity[SUBJ] ^ (horiz[SUBJ]!=NH)); - tl= (parity[CLIP] ^ (horiz[CLIP]!=NH) ^ edge->bundle[BELOW][CLIP]) - || (parity[SUBJ] ^ (horiz[SUBJ]!=NH) ^ edge->bundle[BELOW][SUBJ]); - break; - } - - /* Update parity */ - parity[CLIP]^= edge->bundle[ABOVE][CLIP]; - parity[SUBJ]^= edge->bundle[ABOVE][SUBJ]; - - /* Update horizontal state */ - if (exists[CLIP]) - horiz[CLIP]= - next_h_state[horiz[CLIP]] - [((exists[CLIP] - 1) << 1) + parity[CLIP]]; - if (exists[SUBJ]) - horiz[SUBJ]= - next_h_state[horiz[SUBJ]] - [((exists[SUBJ] - 1) << 1) + parity[SUBJ]]; - - vclass= tr + (tl << 1) + (br << 2) + (bl << 3); - - if (contributing) - { - xb= edge->xb; - - switch (vclass) - { - case EMN: - case IMN: - add_local_min(&out_poly, edge, xb, yb); - px= xb; - cf= edge->outp[ABOVE]; - break; - case ERI: - if (xb != px) - { - add_right(cf, xb, yb); - px= xb; - } - edge->outp[ABOVE]= cf; - cf= NULL; - break; - case ELI: - add_left(edge->outp[BELOW], xb, yb); - px= xb; - cf= edge->outp[BELOW]; - break; - case EMX: - if (xb != px) - { - add_left(cf, xb, yb); - px= xb; - } - merge_right(cf, edge->outp[BELOW], out_poly); - cf= NULL; - break; - case ILI: - if (xb != px) - { - add_left(cf, xb, yb); - px= xb; - } - edge->outp[ABOVE]= cf; - cf= NULL; - break; - case IRI: - add_right(edge->outp[BELOW], xb, yb); - px= xb; - cf= edge->outp[BELOW]; - edge->outp[BELOW]= NULL; - break; - case IMX: - if (xb != px) - { - add_right(cf, xb, yb); - px= xb; - } - merge_left(cf, edge->outp[BELOW], out_poly); - cf= NULL; - edge->outp[BELOW]= NULL; - break; - case IMM: - if (xb != px) - { - add_right(cf, xb, yb); - px= xb; - } - merge_left(cf, edge->outp[BELOW], out_poly); - edge->outp[BELOW]= NULL; - add_local_min(&out_poly, edge, xb, yb); - cf= edge->outp[ABOVE]; - break; - case EMM: - if (xb != px) - { - add_left(cf, xb, yb); - px= xb; - } - merge_right(cf, edge->outp[BELOW], out_poly); - edge->outp[BELOW]= NULL; - add_local_min(&out_poly, edge, xb, yb); - cf= edge->outp[ABOVE]; - break; - case LED: - if (edge->bot.y == yb) - add_left(edge->outp[BELOW], xb, yb); - edge->outp[ABOVE]= edge->outp[BELOW]; - px= xb; - break; - case RED: - if (edge->bot.y == yb) - add_right(edge->outp[BELOW], xb, yb); - edge->outp[ABOVE]= edge->outp[BELOW]; - px= xb; - break; - default: - break; - } /* End of switch */ - } /* End of contributing conditional */ - } /* End of edge exists conditional */ - } /* End of AET loop */ - - /* Delete terminating edges from the AET, otherwise compute xt */ - for (edge= aet; edge; edge= edge->next) - { - if (edge->top.y == yb) - { - prev_edge= edge->prev; - next_edge= edge->next; - if (prev_edge) - prev_edge->next= next_edge; - else - aet= next_edge; - if (next_edge) - next_edge->prev= prev_edge; - - /* Copy bundle head state to the adjacent tail edge if required */ - if ((edge->bstate[BELOW] == BUNDLE_HEAD) && prev_edge) + { + next_edge->bundle[ABOVE][ next_edge->type]^= + e0->bundle[ABOVE][ next_edge->type]; + next_edge->bundle[ABOVE][!next_edge->type]= + e0->bundle[ABOVE][!next_edge->type]; + next_edge->bstate[ABOVE]= BUNDLE_HEAD; + e0->bundle[ABOVE][CLIP]= FALSE; + e0->bundle[ABOVE][SUBJ]= FALSE; + e0->bstate[ABOVE]= BUNDLE_TAIL; + } + e0= next_edge; + } + } + + horiz[CLIP]= NH; + horiz[SUBJ]= NH; + + /* Process each edge at this scanbeam boundary */ + for (edge= aet; edge; edge= edge->next) + { + exists[CLIP]= edge->bundle[ABOVE][CLIP] + + (edge->bundle[BELOW][CLIP] << 1); + exists[SUBJ]= edge->bundle[ABOVE][SUBJ] + + (edge->bundle[BELOW][SUBJ] << 1); + + if (exists[CLIP] || exists[SUBJ]) + { + /* Set bundle side */ + edge->bside[CLIP]= parity[CLIP]; + edge->bside[SUBJ]= parity[SUBJ]; + + /* Determine contributing status and quadrant occupancies */ + switch (op) + { + case GPC_DIFF: + case GPC_INT: + contributing= (exists[CLIP] && (parity[SUBJ] || horiz[SUBJ])) + || (exists[SUBJ] && (parity[CLIP] || horiz[CLIP])) + || (exists[CLIP] && exists[SUBJ] + && (parity[CLIP] == parity[SUBJ])); + br= (parity[CLIP]) + && (parity[SUBJ]); + bl= (parity[CLIP] ^ edge->bundle[ABOVE][CLIP]) + && (parity[SUBJ] ^ edge->bundle[ABOVE][SUBJ]); + tr= (parity[CLIP] ^ (horiz[CLIP]!=NH)) + && (parity[SUBJ] ^ (horiz[SUBJ]!=NH)); + tl= (parity[CLIP] ^ (horiz[CLIP]!=NH) ^ edge->bundle[BELOW][CLIP]) + && (parity[SUBJ] ^ (horiz[SUBJ]!=NH) ^ edge->bundle[BELOW][SUBJ]); + break; + case GPC_XOR: + contributing= exists[CLIP] || exists[SUBJ]; + br= (parity[CLIP]) + ^ (parity[SUBJ]); + bl= (parity[CLIP] ^ edge->bundle[ABOVE][CLIP]) + ^ (parity[SUBJ] ^ edge->bundle[ABOVE][SUBJ]); + tr= (parity[CLIP] ^ (horiz[CLIP]!=NH)) + ^ (parity[SUBJ] ^ (horiz[SUBJ]!=NH)); + tl= (parity[CLIP] ^ (horiz[CLIP]!=NH) ^ edge->bundle[BELOW][CLIP]) + ^ (parity[SUBJ] ^ (horiz[SUBJ]!=NH) ^ edge->bundle[BELOW][SUBJ]); + break; + case GPC_UNION: + contributing= (exists[CLIP] && (!parity[SUBJ] || horiz[SUBJ])) + || (exists[SUBJ] && (!parity[CLIP] || horiz[CLIP])) + || (exists[CLIP] && exists[SUBJ] + && (parity[CLIP] == parity[SUBJ])); + br= (parity[CLIP]) + || (parity[SUBJ]); + bl= (parity[CLIP] ^ edge->bundle[ABOVE][CLIP]) + || (parity[SUBJ] ^ edge->bundle[ABOVE][SUBJ]); + tr= (parity[CLIP] ^ (horiz[CLIP]!=NH)) + || (parity[SUBJ] ^ (horiz[SUBJ]!=NH)); + tl= (parity[CLIP] ^ (horiz[CLIP]!=NH) ^ edge->bundle[BELOW][CLIP]) + || (parity[SUBJ] ^ (horiz[SUBJ]!=NH) ^ edge->bundle[BELOW][SUBJ]); + break; + } + + /* Update parity */ + parity[CLIP]^= edge->bundle[ABOVE][CLIP]; + parity[SUBJ]^= edge->bundle[ABOVE][SUBJ]; + + /* Update horizontal state */ + if (exists[CLIP]) + horiz[CLIP]= + next_h_state[horiz[CLIP]] + [((exists[CLIP] - 1) << 1) + parity[CLIP]]; + if (exists[SUBJ]) + horiz[SUBJ]= + next_h_state[horiz[SUBJ]] + [((exists[SUBJ] - 1) << 1) + parity[SUBJ]]; + + vclass= tr + (tl << 1) + (br << 2) + (bl << 3); + + if (contributing) + { + xb= edge->xb; + + switch (vclass) + { + case EMN: + case IMN: + add_local_min(&out_poly, edge, xb, yb); + px= xb; + cf= edge->outp[ABOVE]; + break; + case ERI: + if (xb != px) + { + add_right(cf, xb, yb); + px= xb; + } + edge->outp[ABOVE]= cf; + cf= NULL; + break; + case ELI: + add_left(edge->outp[BELOW], xb, yb); + px= xb; + cf= edge->outp[BELOW]; + break; + case EMX: + if (xb != px) + { + add_left(cf, xb, yb); + px= xb; + } + merge_right(cf, edge->outp[BELOW], out_poly); + cf= NULL; + break; + case ILI: + if (xb != px) + { + add_left(cf, xb, yb); + px= xb; + } + edge->outp[ABOVE]= cf; + cf= NULL; + break; + case IRI: + add_right(edge->outp[BELOW], xb, yb); + px= xb; + cf= edge->outp[BELOW]; + edge->outp[BELOW]= NULL; + break; + case IMX: + if (xb != px) + { + add_right(cf, xb, yb); + px= xb; + } + merge_left(cf, edge->outp[BELOW], out_poly); + cf= NULL; + edge->outp[BELOW]= NULL; + break; + case IMM: + if (xb != px) + { + add_right(cf, xb, yb); + px= xb; + } + merge_left(cf, edge->outp[BELOW], out_poly); + edge->outp[BELOW]= NULL; + add_local_min(&out_poly, edge, xb, yb); + cf= edge->outp[ABOVE]; + break; + case EMM: + if (xb != px) + { + add_left(cf, xb, yb); + px= xb; + } + merge_right(cf, edge->outp[BELOW], out_poly); + edge->outp[BELOW]= NULL; + add_local_min(&out_poly, edge, xb, yb); + cf= edge->outp[ABOVE]; + break; + case LED: + if (edge->bot.y == yb) + add_left(edge->outp[BELOW], xb, yb); + edge->outp[ABOVE]= edge->outp[BELOW]; + px= xb; + break; + case RED: + if (edge->bot.y == yb) + add_right(edge->outp[BELOW], xb, yb); + edge->outp[ABOVE]= edge->outp[BELOW]; + px= xb; + break; + default: + break; + } /* End of switch */ + } /* End of contributing conditional */ + } /* End of edge exists conditional */ + } /* End of AET loop */ + + /* Delete terminating edges from the AET, otherwise compute xt */ + for (edge= aet; edge; edge= edge->next) + { + if (edge->top.y == yb) + { + prev_edge= edge->prev; + next_edge= edge->next; + if (prev_edge) + prev_edge->next= next_edge; + else + aet= next_edge; + if (next_edge) + next_edge->prev= prev_edge; + + /* Copy bundle head state to the adjacent tail edge if required */ + if ((edge->bstate[BELOW] == BUNDLE_HEAD) && prev_edge) { - if (prev_edge->bstate[BELOW] == BUNDLE_TAIL) - { - prev_edge->outp[BELOW]= edge->outp[BELOW]; - prev_edge->bstate[BELOW]= UNBUNDLED; - if (prev_edge->prev) - if (prev_edge->prev->bstate[BELOW] == BUNDLE_TAIL) - prev_edge->bstate[BELOW]= BUNDLE_HEAD; + if (prev_edge->bstate[BELOW] == BUNDLE_TAIL) + { + prev_edge->outp[BELOW]= edge->outp[BELOW]; + prev_edge->bstate[BELOW]= UNBUNDLED; + if (prev_edge->prev) + if (prev_edge->prev->bstate[BELOW] == BUNDLE_TAIL) + prev_edge->bstate[BELOW]= BUNDLE_HEAD; } } - } - else - { - if (edge->top.y == yt) - edge->xt= edge->top.x; - else - edge->xt= edge->bot.x + edge->dx * (yt - edge->bot.y); - } - } - - if (scanbeam < sbt_entries) - { - /* === SCANBEAM INTERIOR PROCESSING ============================== */ - - build_intersection_table(&it, aet, dy); - - /* Process each node in the intersection table */ - for (intersect= it; intersect; intersect= intersect->next) - { - e0= intersect->ie[0]; - e1= intersect->ie[1]; - - /* Only generate output for contributing intersections */ - if ((e0->bundle[ABOVE][CLIP] || e0->bundle[ABOVE][SUBJ]) - && (e1->bundle[ABOVE][CLIP] || e1->bundle[ABOVE][SUBJ])) + } + else + { + if (edge->top.y == yt) + edge->xt= edge->top.x; + else + edge->xt= edge->bot.x + edge->dx * (yt - edge->bot.y); + } + } + + if (scanbeam < sbt_entries) + { + /* === SCANBEAM INTERIOR PROCESSING ============================== */ + + build_intersection_table(&it, aet, dy); + + /* Process each node in the intersection table */ + for (intersect= it; intersect; intersect= intersect->next) + { + e0= intersect->ie[0]; + e1= intersect->ie[1]; + + /* Only generate output for contributing intersections */ + if ((e0->bundle[ABOVE][CLIP] || e0->bundle[ABOVE][SUBJ]) + && (e1->bundle[ABOVE][CLIP] || e1->bundle[ABOVE][SUBJ])) { - p= e0->outp[ABOVE]; - q= e1->outp[ABOVE]; - ix= intersect->point.x; - iy= intersect->point.y + yb; - - in[CLIP]= ( e0->bundle[ABOVE][CLIP] && !e0->bside[CLIP]) - || ( e1->bundle[ABOVE][CLIP] && e1->bside[CLIP]) - || (!e0->bundle[ABOVE][CLIP] && !e1->bundle[ABOVE][CLIP] - && e0->bside[CLIP] && e1->bside[CLIP]); - in[SUBJ]= ( e0->bundle[ABOVE][SUBJ] && !e0->bside[SUBJ]) - || ( e1->bundle[ABOVE][SUBJ] && e1->bside[SUBJ]) - || (!e0->bundle[ABOVE][SUBJ] && !e1->bundle[ABOVE][SUBJ] - && e0->bside[SUBJ] && e1->bside[SUBJ]); - - /* Determine quadrant occupancies */ - switch (op) - { - case GPC_DIFF: - case GPC_INT: - tr= (in[CLIP]) - && (in[SUBJ]); - tl= (in[CLIP] ^ e1->bundle[ABOVE][CLIP]) - && (in[SUBJ] ^ e1->bundle[ABOVE][SUBJ]); - br= (in[CLIP] ^ e0->bundle[ABOVE][CLIP]) - && (in[SUBJ] ^ e0->bundle[ABOVE][SUBJ]); - bl= (in[CLIP] ^ e1->bundle[ABOVE][CLIP] ^ e0->bundle[ABOVE][CLIP]) - && (in[SUBJ] ^ e1->bundle[ABOVE][SUBJ] ^ e0->bundle[ABOVE][SUBJ]); - break; - case GPC_XOR: - tr= (in[CLIP]) - ^ (in[SUBJ]); - tl= (in[CLIP] ^ e1->bundle[ABOVE][CLIP]) - ^ (in[SUBJ] ^ e1->bundle[ABOVE][SUBJ]); - br= (in[CLIP] ^ e0->bundle[ABOVE][CLIP]) - ^ (in[SUBJ] ^ e0->bundle[ABOVE][SUBJ]); - bl= (in[CLIP] ^ e1->bundle[ABOVE][CLIP] ^ e0->bundle[ABOVE][CLIP]) - ^ (in[SUBJ] ^ e1->bundle[ABOVE][SUBJ] ^ e0->bundle[ABOVE][SUBJ]); - break; - case GPC_UNION: - tr= (in[CLIP]) - || (in[SUBJ]); - tl= (in[CLIP] ^ e1->bundle[ABOVE][CLIP]) - || (in[SUBJ] ^ e1->bundle[ABOVE][SUBJ]); - br= (in[CLIP] ^ e0->bundle[ABOVE][CLIP]) - || (in[SUBJ] ^ e0->bundle[ABOVE][SUBJ]); - bl= (in[CLIP] ^ e1->bundle[ABOVE][CLIP] ^ e0->bundle[ABOVE][CLIP]) - || (in[SUBJ] ^ e1->bundle[ABOVE][SUBJ] ^ e0->bundle[ABOVE][SUBJ]); - break; - } - - vclass= tr + (tl << 1) + (br << 2) + (bl << 3); - - switch (vclass) - { - case EMN: - add_local_min(&out_poly, e0, ix, iy); - e1->outp[ABOVE]= e0->outp[ABOVE]; - break; - case ERI: - if (p) - { - add_right(p, ix, iy); - e1->outp[ABOVE]= p; - e0->outp[ABOVE]= NULL; - } - break; - case ELI: - if (q) - { - add_left(q, ix, iy); - e0->outp[ABOVE]= q; - e1->outp[ABOVE]= NULL; - } - break; - case EMX: - if (p && q) - { - add_left(p, ix, iy); - merge_right(p, q, out_poly); - e0->outp[ABOVE]= NULL; - e1->outp[ABOVE]= NULL; - } - break; - case IMN: - add_local_min(&out_poly, e0, ix, iy); - e1->outp[ABOVE]= e0->outp[ABOVE]; - break; - case ILI: - if (p) - { - add_left(p, ix, iy); - e1->outp[ABOVE]= p; - e0->outp[ABOVE]= NULL; - } - break; - case IRI: - if (q) - { - add_right(q, ix, iy); - e0->outp[ABOVE]= q; - e1->outp[ABOVE]= NULL; - } - break; - case IMX: - if (p && q) - { - add_right(p, ix, iy); - merge_left(p, q, out_poly); - e0->outp[ABOVE]= NULL; - e1->outp[ABOVE]= NULL; - } - break; - case IMM: - if (p && q) - { - add_right(p, ix, iy); - merge_left(p, q, out_poly); - add_local_min(&out_poly, e0, ix, iy); - e1->outp[ABOVE]= e0->outp[ABOVE]; - } - break; - case EMM: - if (p && q) - { - add_left(p, ix, iy); - merge_right(p, q, out_poly); - add_local_min(&out_poly, e0, ix, iy); - e1->outp[ABOVE]= e0->outp[ABOVE]; - } - break; - default: - break; - } /* End of switch */ + p= e0->outp[ABOVE]; + q= e1->outp[ABOVE]; + ix= intersect->point.x; + iy= intersect->point.y + yb; + + in[CLIP]= ( e0->bundle[ABOVE][CLIP] && !e0->bside[CLIP]) + || ( e1->bundle[ABOVE][CLIP] && e1->bside[CLIP]) + || (!e0->bundle[ABOVE][CLIP] && !e1->bundle[ABOVE][CLIP] + && e0->bside[CLIP] && e1->bside[CLIP]); + in[SUBJ]= ( e0->bundle[ABOVE][SUBJ] && !e0->bside[SUBJ]) + || ( e1->bundle[ABOVE][SUBJ] && e1->bside[SUBJ]) + || (!e0->bundle[ABOVE][SUBJ] && !e1->bundle[ABOVE][SUBJ] + && e0->bside[SUBJ] && e1->bside[SUBJ]); + + /* Determine quadrant occupancies */ + switch (op) + { + case GPC_DIFF: + case GPC_INT: + tr= (in[CLIP]) + && (in[SUBJ]); + tl= (in[CLIP] ^ e1->bundle[ABOVE][CLIP]) + && (in[SUBJ] ^ e1->bundle[ABOVE][SUBJ]); + br= (in[CLIP] ^ e0->bundle[ABOVE][CLIP]) + && (in[SUBJ] ^ e0->bundle[ABOVE][SUBJ]); + bl= (in[CLIP] ^ e1->bundle[ABOVE][CLIP] ^ e0->bundle[ABOVE][CLIP]) + && (in[SUBJ] ^ e1->bundle[ABOVE][SUBJ] ^ e0->bundle[ABOVE][SUBJ]); + break; + case GPC_XOR: + tr= (in[CLIP]) + ^ (in[SUBJ]); + tl= (in[CLIP] ^ e1->bundle[ABOVE][CLIP]) + ^ (in[SUBJ] ^ e1->bundle[ABOVE][SUBJ]); + br= (in[CLIP] ^ e0->bundle[ABOVE][CLIP]) + ^ (in[SUBJ] ^ e0->bundle[ABOVE][SUBJ]); + bl= (in[CLIP] ^ e1->bundle[ABOVE][CLIP] ^ e0->bundle[ABOVE][CLIP]) + ^ (in[SUBJ] ^ e1->bundle[ABOVE][SUBJ] ^ e0->bundle[ABOVE][SUBJ]); + break; + case GPC_UNION: + tr= (in[CLIP]) + || (in[SUBJ]); + tl= (in[CLIP] ^ e1->bundle[ABOVE][CLIP]) + || (in[SUBJ] ^ e1->bundle[ABOVE][SUBJ]); + br= (in[CLIP] ^ e0->bundle[ABOVE][CLIP]) + || (in[SUBJ] ^ e0->bundle[ABOVE][SUBJ]); + bl= (in[CLIP] ^ e1->bundle[ABOVE][CLIP] ^ e0->bundle[ABOVE][CLIP]) + || (in[SUBJ] ^ e1->bundle[ABOVE][SUBJ] ^ e0->bundle[ABOVE][SUBJ]); + break; + } + + vclass= tr + (tl << 1) + (br << 2) + (bl << 3); + + switch (vclass) + { + case EMN: + add_local_min(&out_poly, e0, ix, iy); + e1->outp[ABOVE]= e0->outp[ABOVE]; + break; + case ERI: + if (p) + { + add_right(p, ix, iy); + e1->outp[ABOVE]= p; + e0->outp[ABOVE]= NULL; + } + break; + case ELI: + if (q) + { + add_left(q, ix, iy); + e0->outp[ABOVE]= q; + e1->outp[ABOVE]= NULL; + } + break; + case EMX: + if (p && q) + { + add_left(p, ix, iy); + merge_right(p, q, out_poly); + e0->outp[ABOVE]= NULL; + e1->outp[ABOVE]= NULL; + } + break; + case IMN: + add_local_min(&out_poly, e0, ix, iy); + e1->outp[ABOVE]= e0->outp[ABOVE]; + break; + case ILI: + if (p) + { + add_left(p, ix, iy); + e1->outp[ABOVE]= p; + e0->outp[ABOVE]= NULL; + } + break; + case IRI: + if (q) + { + add_right(q, ix, iy); + e0->outp[ABOVE]= q; + e1->outp[ABOVE]= NULL; + } + break; + case IMX: + if (p && q) + { + add_right(p, ix, iy); + merge_left(p, q, out_poly); + e0->outp[ABOVE]= NULL; + e1->outp[ABOVE]= NULL; + } + break; + case IMM: + if (p && q) + { + add_right(p, ix, iy); + merge_left(p, q, out_poly); + add_local_min(&out_poly, e0, ix, iy); + e1->outp[ABOVE]= e0->outp[ABOVE]; + } + break; + case EMM: + if (p && q) + { + add_left(p, ix, iy); + merge_right(p, q, out_poly); + add_local_min(&out_poly, e0, ix, iy); + e1->outp[ABOVE]= e0->outp[ABOVE]; + } + break; + default: + break; + } /* End of switch */ } /* End of contributing intersection conditional */ - /* Swap bundle sides in response to edge crossing */ - if (e0->bundle[ABOVE][CLIP]) + /* Swap bundle sides in response to edge crossing */ + if (e0->bundle[ABOVE][CLIP]) e1->bside[CLIP]= !e1->bside[CLIP]; - if (e1->bundle[ABOVE][CLIP]) + if (e1->bundle[ABOVE][CLIP]) e0->bside[CLIP]= !e0->bside[CLIP]; - if (e0->bundle[ABOVE][SUBJ]) + if (e0->bundle[ABOVE][SUBJ]) e1->bside[SUBJ]= !e1->bside[SUBJ]; - if (e1->bundle[ABOVE][SUBJ]) + if (e1->bundle[ABOVE][SUBJ]) e0->bside[SUBJ]= !e0->bside[SUBJ]; - /* Swap e0 and e1 bundles in the AET */ - prev_edge= e0->prev; - next_edge= e1->next; - if (next_edge) - next_edge->prev= e0; - - if (e0->bstate[ABOVE] == BUNDLE_HEAD) - { - search= TRUE; - while (search) - { - prev_edge= prev_edge->prev; - if (prev_edge) - { - if (prev_edge->bstate[ABOVE] != BUNDLE_TAIL) - search= FALSE; - } - else - search= FALSE; - } - } - if (!prev_edge) - { - aet->prev= e1; - e1->next= aet; - aet= e0->next; - } - else - { - prev_edge->next->prev= e1; - e1->next= prev_edge->next; - prev_edge->next= e0->next; - } + /* Swap e0 and e1 bundles in the AET */ + prev_edge= e0->prev; + next_edge= e1->next; + if (next_edge) + next_edge->prev= e0; + + if (e0->bstate[ABOVE] == BUNDLE_HEAD) + { + search= TRUE; + while (search) + { + prev_edge= prev_edge->prev; + if (prev_edge) + { + if (prev_edge->bstate[ABOVE] != BUNDLE_TAIL) + search= FALSE; + } + else + search= FALSE; + } + } + if (!prev_edge) + { + aet->prev= e1; + e1->next= aet; + aet= e0->next; + } + else + { + prev_edge->next->prev= e1; + e1->next= prev_edge->next; + prev_edge->next= e0->next; + } if(e0->next == NULL) throw runtime_error("GPC internal error.") ; if(e1->next == NULL) throw runtime_error("GPC internal error.") ; - e0->next->prev= prev_edge; - e1->next->prev= e1; - e0->next= next_edge; - } /* End of IT loop*/ - - /* Prepare for next scanbeam */ - for (edge= aet; edge; edge= next_edge) - { - next_edge= edge->next; - succ_edge= edge->succ; - - if ((edge->top.y == yt) && succ_edge) - { - /* Replace AET edge by its successor */ - succ_edge->outp[BELOW]= edge->outp[ABOVE]; - succ_edge->bstate[BELOW]= edge->bstate[ABOVE]; - succ_edge->bundle[BELOW][CLIP]= edge->bundle[ABOVE][CLIP]; - succ_edge->bundle[BELOW][SUBJ]= edge->bundle[ABOVE][SUBJ]; - prev_edge= edge->prev; - if (prev_edge) - prev_edge->next= succ_edge; - else - aet= succ_edge; - if (next_edge) - next_edge->prev= succ_edge; - succ_edge->prev= prev_edge; - succ_edge->next= next_edge; - } - else - { - /* Update this edge */ - edge->outp[BELOW]= edge->outp[ABOVE]; - edge->bstate[BELOW]= edge->bstate[ABOVE]; - edge->bundle[BELOW][CLIP]= edge->bundle[ABOVE][CLIP]; - edge->bundle[BELOW][SUBJ]= edge->bundle[ABOVE][SUBJ]; - edge->xb= edge->xt; - } - edge->outp[ABOVE]= NULL; - } - } + e0->next->prev= prev_edge; + e1->next->prev= e1; + e0->next= next_edge; + } /* End of IT loop*/ + + /* Prepare for next scanbeam */ + for (edge= aet; edge; edge= next_edge) + { + next_edge= edge->next; + succ_edge= edge->succ; + + if ((edge->top.y == yt) && succ_edge) + { + /* Replace AET edge by its successor */ + succ_edge->outp[BELOW]= edge->outp[ABOVE]; + succ_edge->bstate[BELOW]= edge->bstate[ABOVE]; + succ_edge->bundle[BELOW][CLIP]= edge->bundle[ABOVE][CLIP]; + succ_edge->bundle[BELOW][SUBJ]= edge->bundle[ABOVE][SUBJ]; + prev_edge= edge->prev; + if (prev_edge) + prev_edge->next= succ_edge; + else + aet= succ_edge; + if (next_edge) + next_edge->prev= succ_edge; + succ_edge->prev= prev_edge; + succ_edge->next= next_edge; + } + else + { + /* Update this edge */ + edge->outp[BELOW]= edge->outp[ABOVE]; + edge->bstate[BELOW]= edge->bstate[ABOVE]; + edge->bundle[BELOW][CLIP]= edge->bundle[ABOVE][CLIP]; + edge->bundle[BELOW][SUBJ]= edge->bundle[ABOVE][SUBJ]; + edge->xb= edge->xt; + } + edge->outp[ABOVE]= NULL; + } + } } /* === END OF SCANBEAM PROCESSING ================================== */ /* Generate result polygon from out_poly */ @@ -1780,44 +1777,44 @@ void gpc_polygon_clip(gpc_op op, gpc_polygon *subj, gpc_polygon *clip, result->num_contours= count_contours(out_poly); if (result->num_contours > 0) { - MALLOC(result->hole, result->num_contours - * sizeof(int), "hole flag table creation", int); - MALLOC(result->contour, result->num_contours - * sizeof(gpc_vertex_list), "contour creation", gpc_vertex_list); - - c= 0; - for (poly= out_poly; poly; poly= npoly) - { - npoly= poly->next; - if (poly->active) - { - result->hole[c]= poly->proxy->hole; - result->contour[c].num_vertices= poly->active; - MALLOC(result->contour[c].vertex, - result->contour[c].num_vertices * sizeof(gpc_vertex), - "vertex creation", gpc_vertex); - - v= result->contour[c].num_vertices - 1; - for (vtx= poly->proxy->v[LEFT]; vtx; vtx= nv) - { - nv= vtx->next; - result->contour[c].vertex[v].x= vtx->x; - result->contour[c].vertex[v].y= vtx->y; - FREE(vtx); - v--; - } - c++; - } - FREE(poly); - } + MALLOC(result->hole, result->num_contours + * sizeof(int), "hole flag table creation", int); + MALLOC(result->contour, result->num_contours + * sizeof(gpc_vertex_list), "contour creation", gpc_vertex_list); + + c= 0; + for (poly= out_poly; poly; poly= npoly) + { + npoly= poly->next; + if (poly->active) + { + result->hole[c]= poly->proxy->hole; + result->contour[c].num_vertices= poly->active; + MALLOC(result->contour[c].vertex, + result->contour[c].num_vertices * sizeof(gpc_vertex), + "vertex creation", gpc_vertex); + + v= result->contour[c].num_vertices - 1; + for (vtx= poly->proxy->v[LEFT]; vtx; vtx= nv) + { + nv= vtx->next; + result->contour[c].vertex[v].x= vtx->x; + result->contour[c].vertex[v].y= vtx->y; + FREE(vtx); + v--; + } + c++; + } + FREE(poly); + } } else { - for (poly= out_poly; poly; poly= npoly) - { - npoly= poly->next; - FREE(poly); - } + for (poly= out_poly; poly; poly= npoly) + { + npoly= poly->next; + FREE(poly); + } } /* Tidy up */ @@ -1831,10 +1828,8 @@ void gpc_polygon_clip(gpc_op op, gpc_polygon *subj, gpc_polygon *clip, void gpc_free_tristrip(gpc_tristrip *t) { - int s; - - for (s= 0; s < t->num_strips; s++) - FREE(t->strip[s].vertex); + for (size_t s= 0; s < t->num_strips; s++) + FREE(t->strip[s].vertex); FREE(t->strip); t->num_strips= 0; } @@ -1852,7 +1847,7 @@ void gpc_polygon_to_tristrip(gpc_polygon *s, gpc_tristrip *t) void gpc_tristrip_clip(gpc_op op, gpc_polygon *subj, gpc_polygon *clip, - gpc_tristrip *result) + gpc_tristrip *result) { sb_tree *sbtree= NULL; it_node *it= NULL, *intersect; @@ -1873,31 +1868,31 @@ void gpc_tristrip_clip(gpc_op op, gpc_polygon *subj, gpc_polygon *clip, || ((subj->num_contours == 0) && ((op == GPC_INT) || (op == GPC_DIFF))) || ((clip->num_contours == 0) && (op == GPC_INT))) { - result->num_strips= 0; - result->strip= NULL; - return; + result->num_strips= 0; + result->strip= NULL; + return; } /* Identify potentialy contributing contours */ if (((op == GPC_INT) || (op == GPC_DIFF)) && (subj->num_contours > 0) && (clip->num_contours > 0)) - minimax_test(subj, clip, op); + minimax_test(subj, clip, op); /* Build LMT */ if (subj->num_contours > 0) - s_heap= build_lmt(&lmt, &sbtree, &sbt_entries, subj, SUBJ, op); + s_heap= build_lmt(&lmt, &sbtree, &sbt_entries, subj, SUBJ, op); if (clip->num_contours > 0) - c_heap= build_lmt(&lmt, &sbtree, &sbt_entries, clip, CLIP, op); + c_heap= build_lmt(&lmt, &sbtree, &sbt_entries, clip, CLIP, op); /* Return a NULL result if no contours contribute */ if (lmt == NULL) { - result->num_strips= 0; - result->strip= NULL; - reset_lmt(&lmt); - FREE(s_heap); - FREE(c_heap); - return; + result->num_strips= 0; + result->strip= NULL; + reset_lmt(&lmt); + FREE(s_heap); + FREE(c_heap); + return; } /* Build scanbeam table from scanbeam tree */ @@ -1908,559 +1903,559 @@ void gpc_tristrip_clip(gpc_op op, gpc_polygon *subj, gpc_polygon *clip, /* Invert clip polygon for difference operation */ if (op == GPC_DIFF) - parity[CLIP]= RIGHT; + parity[CLIP]= RIGHT; local_min= lmt; /* Process each scanbeam */ while (scanbeam < sbt_entries) { - /* Set yb and yt to the bottom and top of the scanbeam */ - yb= sbt[scanbeam++]; - if (scanbeam < sbt_entries) - { - yt= sbt[scanbeam]; - dy= yt - yb; - } - - /* === SCANBEAM BOUNDARY PROCESSING ================================ */ - - /* If LMT node corresponding to yb exists */ - if (local_min) - { - if (local_min->y == yb) - { - /* Add edges starting at this local minimum to the AET */ - for (edge= local_min->first_bound; edge; edge= edge->next_bound) - add_edge_to_aet(&aet, edge, NULL); - - local_min= local_min->next; - } - } - - /* Set dummy previous x value */ - px= -DBL_MAX; - - /* Create bundles within AET */ - e0= aet; - e1= aet; - - /* Set up bundle fields of first edge */ - aet->bundle[ABOVE][ aet->type]= (aet->top.y != yb); - aet->bundle[ABOVE][!aet->type]= FALSE; - aet->bstate[ABOVE]= UNBUNDLED; - - for (next_edge= aet->next; next_edge; next_edge= next_edge->next) - { - /* Set up bundle fields of next edge */ - next_edge->bundle[ABOVE][ next_edge->type]= (next_edge->top.y != yb); - next_edge->bundle[ABOVE][!next_edge->type]= FALSE; - next_edge->bstate[ABOVE]= UNBUNDLED; - - /* Bundle edges above the scanbeam boundary if they coincide */ - if (next_edge->bundle[ABOVE][next_edge->type]) - { - if (EQ(e0->xb, next_edge->xb) && EQ(e0->dx, next_edge->dx) + /* Set yb and yt to the bottom and top of the scanbeam */ + yb= sbt[scanbeam++]; + if (scanbeam < sbt_entries) + { + yt= sbt[scanbeam]; + dy= yt - yb; + } + + /* === SCANBEAM BOUNDARY PROCESSING ================================ */ + + /* If LMT node corresponding to yb exists */ + if (local_min) + { + if (local_min->y == yb) + { + /* Add edges starting at this local minimum to the AET */ + for (edge= local_min->first_bound; edge; edge= edge->next_bound) + add_edge_to_aet(&aet, edge, NULL); + + local_min= local_min->next; + } + } + + /* Set dummy previous x value */ + px= -DBL_MAX; + + /* Create bundles within AET */ + e0= aet; + e1= aet; + + /* Set up bundle fields of first edge */ + aet->bundle[ABOVE][ aet->type]= (aet->top.y != yb); + aet->bundle[ABOVE][!aet->type]= FALSE; + aet->bstate[ABOVE]= UNBUNDLED; + + for (next_edge= aet->next; next_edge; next_edge= next_edge->next) + { + /* Set up bundle fields of next edge */ + next_edge->bundle[ABOVE][ next_edge->type]= (next_edge->top.y != yb); + next_edge->bundle[ABOVE][!next_edge->type]= FALSE; + next_edge->bstate[ABOVE]= UNBUNDLED; + + /* Bundle edges above the scanbeam boundary if they coincide */ + if (next_edge->bundle[ABOVE][next_edge->type]) + { + if (EQ(e0->xb, next_edge->xb) && EQ(e0->dx, next_edge->dx) && (e0->top.y != yb)) - { - next_edge->bundle[ABOVE][ next_edge->type]^= - e0->bundle[ABOVE][ next_edge->type]; - next_edge->bundle[ABOVE][!next_edge->type]= - e0->bundle[ABOVE][!next_edge->type]; - next_edge->bstate[ABOVE]= BUNDLE_HEAD; - e0->bundle[ABOVE][CLIP]= FALSE; - e0->bundle[ABOVE][SUBJ]= FALSE; - e0->bstate[ABOVE]= BUNDLE_TAIL; - } - e0= next_edge; - } - } - - horiz[CLIP]= NH; - horiz[SUBJ]= NH; - - /* Process each edge at this scanbeam boundary */ - for (edge= aet; edge; edge= edge->next) - { - exists[CLIP]= edge->bundle[ABOVE][CLIP] + - (edge->bundle[BELOW][CLIP] << 1); - exists[SUBJ]= edge->bundle[ABOVE][SUBJ] + - (edge->bundle[BELOW][SUBJ] << 1); - - if (exists[CLIP] || exists[SUBJ]) - { - /* Set bundle side */ - edge->bside[CLIP]= parity[CLIP]; - edge->bside[SUBJ]= parity[SUBJ]; - - /* Determine contributing status and quadrant occupancies */ - switch (op) - { - case GPC_DIFF: - case GPC_INT: - contributing= (exists[CLIP] && (parity[SUBJ] || horiz[SUBJ])) - || (exists[SUBJ] && (parity[CLIP] || horiz[CLIP])) - || (exists[CLIP] && exists[SUBJ] - && (parity[CLIP] == parity[SUBJ])); - br= (parity[CLIP]) - && (parity[SUBJ]); - bl= (parity[CLIP] ^ edge->bundle[ABOVE][CLIP]) - && (parity[SUBJ] ^ edge->bundle[ABOVE][SUBJ]); - tr= (parity[CLIP] ^ (horiz[CLIP]!=NH)) - && (parity[SUBJ] ^ (horiz[SUBJ]!=NH)); - tl= (parity[CLIP] ^ (horiz[CLIP]!=NH) ^ edge->bundle[BELOW][CLIP]) - && (parity[SUBJ] ^ (horiz[SUBJ]!=NH) ^ edge->bundle[BELOW][SUBJ]); - break; - case GPC_XOR: - contributing= exists[CLIP] || exists[SUBJ]; - br= (parity[CLIP]) - ^ (parity[SUBJ]); - bl= (parity[CLIP] ^ edge->bundle[ABOVE][CLIP]) - ^ (parity[SUBJ] ^ edge->bundle[ABOVE][SUBJ]); - tr= (parity[CLIP] ^ (horiz[CLIP]!=NH)) - ^ (parity[SUBJ] ^ (horiz[SUBJ]!=NH)); - tl= (parity[CLIP] ^ (horiz[CLIP]!=NH) ^ edge->bundle[BELOW][CLIP]) - ^ (parity[SUBJ] ^ (horiz[SUBJ]!=NH) ^ edge->bundle[BELOW][SUBJ]); - break; - case GPC_UNION: - contributing= (exists[CLIP] && (!parity[SUBJ] || horiz[SUBJ])) - || (exists[SUBJ] && (!parity[CLIP] || horiz[CLIP])) - || (exists[CLIP] && exists[SUBJ] - && (parity[CLIP] == parity[SUBJ])); - br= (parity[CLIP]) - || (parity[SUBJ]); - bl= (parity[CLIP] ^ edge->bundle[ABOVE][CLIP]) - || (parity[SUBJ] ^ edge->bundle[ABOVE][SUBJ]); - tr= (parity[CLIP] ^ (horiz[CLIP]!=NH)) - || (parity[SUBJ] ^ (horiz[SUBJ]!=NH)); - tl= (parity[CLIP] ^ (horiz[CLIP]!=NH) ^ edge->bundle[BELOW][CLIP]) - || (parity[SUBJ] ^ (horiz[SUBJ]!=NH) ^ edge->bundle[BELOW][SUBJ]); - break; - } - - /* Update parity */ - parity[CLIP]^= edge->bundle[ABOVE][CLIP]; - parity[SUBJ]^= edge->bundle[ABOVE][SUBJ]; - - /* Update horizontal state */ - if (exists[CLIP]) - horiz[CLIP]= - next_h_state[horiz[CLIP]] - [((exists[CLIP] - 1) << 1) + parity[CLIP]]; - if (exists[SUBJ]) - horiz[SUBJ]= - next_h_state[horiz[SUBJ]] - [((exists[SUBJ] - 1) << 1) + parity[SUBJ]]; - - vclass= tr + (tl << 1) + (br << 2) + (bl << 3); - - if (contributing) - { - xb= edge->xb; - - switch (vclass) - { - case EMN: - new_tristrip(&tlist, edge, xb, yb); - cf= edge; - break; - case ERI: - edge->outp[ABOVE]= cf->outp[ABOVE]; - if (xb != cf->xb) - VERTEX(edge, ABOVE, RIGHT, xb, yb); - cf= NULL; - break; - case ELI: - VERTEX(edge, BELOW, LEFT, xb, yb); - edge->outp[ABOVE]= NULL; - cf= edge; - break; - case EMX: - if (xb != cf->xb) - VERTEX(edge, BELOW, RIGHT, xb, yb); - edge->outp[ABOVE]= NULL; - cf= NULL; - break; - case IMN: - if (cft == LED) - { - if (cf->bot.y != yb) - VERTEX(cf, BELOW, LEFT, cf->xb, yb); - new_tristrip(&tlist, cf, cf->xb, yb); - } - edge->outp[ABOVE]= cf->outp[ABOVE]; - VERTEX(edge, ABOVE, RIGHT, xb, yb); - break; - case ILI: - new_tristrip(&tlist, edge, xb, yb); - cf= edge; - cft= ILI; - break; - case IRI: - if (cft == LED) - { - if (cf->bot.y != yb) - VERTEX(cf, BELOW, LEFT, cf->xb, yb); - new_tristrip(&tlist, cf, cf->xb, yb); - } - VERTEX(edge, BELOW, RIGHT, xb, yb); - edge->outp[ABOVE]= NULL; - break; - case IMX: - VERTEX(edge, BELOW, LEFT, xb, yb); - edge->outp[ABOVE]= NULL; - cft= IMX; - break; + { + next_edge->bundle[ABOVE][ next_edge->type]^= + e0->bundle[ABOVE][ next_edge->type]; + next_edge->bundle[ABOVE][!next_edge->type]= + e0->bundle[ABOVE][!next_edge->type]; + next_edge->bstate[ABOVE]= BUNDLE_HEAD; + e0->bundle[ABOVE][CLIP]= FALSE; + e0->bundle[ABOVE][SUBJ]= FALSE; + e0->bstate[ABOVE]= BUNDLE_TAIL; + } + e0= next_edge; + } + } + + horiz[CLIP]= NH; + horiz[SUBJ]= NH; + + /* Process each edge at this scanbeam boundary */ + for (edge= aet; edge; edge= edge->next) + { + exists[CLIP]= edge->bundle[ABOVE][CLIP] + + (edge->bundle[BELOW][CLIP] << 1); + exists[SUBJ]= edge->bundle[ABOVE][SUBJ] + + (edge->bundle[BELOW][SUBJ] << 1); + + if (exists[CLIP] || exists[SUBJ]) + { + /* Set bundle side */ + edge->bside[CLIP]= parity[CLIP]; + edge->bside[SUBJ]= parity[SUBJ]; + + /* Determine contributing status and quadrant occupancies */ + switch (op) + { + case GPC_DIFF: + case GPC_INT: + contributing= (exists[CLIP] && (parity[SUBJ] || horiz[SUBJ])) + || (exists[SUBJ] && (parity[CLIP] || horiz[CLIP])) + || (exists[CLIP] && exists[SUBJ] + && (parity[CLIP] == parity[SUBJ])); + br= (parity[CLIP]) + && (parity[SUBJ]); + bl= (parity[CLIP] ^ edge->bundle[ABOVE][CLIP]) + && (parity[SUBJ] ^ edge->bundle[ABOVE][SUBJ]); + tr= (parity[CLIP] ^ (horiz[CLIP]!=NH)) + && (parity[SUBJ] ^ (horiz[SUBJ]!=NH)); + tl= (parity[CLIP] ^ (horiz[CLIP]!=NH) ^ edge->bundle[BELOW][CLIP]) + && (parity[SUBJ] ^ (horiz[SUBJ]!=NH) ^ edge->bundle[BELOW][SUBJ]); + break; + case GPC_XOR: + contributing= exists[CLIP] || exists[SUBJ]; + br= (parity[CLIP]) + ^ (parity[SUBJ]); + bl= (parity[CLIP] ^ edge->bundle[ABOVE][CLIP]) + ^ (parity[SUBJ] ^ edge->bundle[ABOVE][SUBJ]); + tr= (parity[CLIP] ^ (horiz[CLIP]!=NH)) + ^ (parity[SUBJ] ^ (horiz[SUBJ]!=NH)); + tl= (parity[CLIP] ^ (horiz[CLIP]!=NH) ^ edge->bundle[BELOW][CLIP]) + ^ (parity[SUBJ] ^ (horiz[SUBJ]!=NH) ^ edge->bundle[BELOW][SUBJ]); + break; + case GPC_UNION: + contributing= (exists[CLIP] && (!parity[SUBJ] || horiz[SUBJ])) + || (exists[SUBJ] && (!parity[CLIP] || horiz[CLIP])) + || (exists[CLIP] && exists[SUBJ] + && (parity[CLIP] == parity[SUBJ])); + br= (parity[CLIP]) + || (parity[SUBJ]); + bl= (parity[CLIP] ^ edge->bundle[ABOVE][CLIP]) + || (parity[SUBJ] ^ edge->bundle[ABOVE][SUBJ]); + tr= (parity[CLIP] ^ (horiz[CLIP]!=NH)) + || (parity[SUBJ] ^ (horiz[SUBJ]!=NH)); + tl= (parity[CLIP] ^ (horiz[CLIP]!=NH) ^ edge->bundle[BELOW][CLIP]) + || (parity[SUBJ] ^ (horiz[SUBJ]!=NH) ^ edge->bundle[BELOW][SUBJ]); + break; + } + + /* Update parity */ + parity[CLIP]^= edge->bundle[ABOVE][CLIP]; + parity[SUBJ]^= edge->bundle[ABOVE][SUBJ]; + + /* Update horizontal state */ + if (exists[CLIP]) + horiz[CLIP]= + next_h_state[horiz[CLIP]] + [((exists[CLIP] - 1) << 1) + parity[CLIP]]; + if (exists[SUBJ]) + horiz[SUBJ]= + next_h_state[horiz[SUBJ]] + [((exists[SUBJ] - 1) << 1) + parity[SUBJ]]; + + vclass= tr + (tl << 1) + (br << 2) + (bl << 3); + + if (contributing) + { + xb= edge->xb; + + switch (vclass) + { + case EMN: + new_tristrip(&tlist, edge, xb, yb); + cf= edge; + break; + case ERI: + edge->outp[ABOVE]= cf->outp[ABOVE]; + if (xb != cf->xb) + VERTEX(edge, ABOVE, RIGHT, xb, yb); + cf= NULL; + break; + case ELI: + VERTEX(edge, BELOW, LEFT, xb, yb); + edge->outp[ABOVE]= NULL; + cf= edge; + break; + case EMX: + if (xb != cf->xb) + VERTEX(edge, BELOW, RIGHT, xb, yb); + edge->outp[ABOVE]= NULL; + cf= NULL; + break; + case IMN: + if (cft == LED) + { + if (cf->bot.y != yb) + VERTEX(cf, BELOW, LEFT, cf->xb, yb); + new_tristrip(&tlist, cf, cf->xb, yb); + } + edge->outp[ABOVE]= cf->outp[ABOVE]; + VERTEX(edge, ABOVE, RIGHT, xb, yb); + break; + case ILI: + new_tristrip(&tlist, edge, xb, yb); + cf= edge; + cft= ILI; + break; + case IRI: + if (cft == LED) + { + if (cf->bot.y != yb) + VERTEX(cf, BELOW, LEFT, cf->xb, yb); + new_tristrip(&tlist, cf, cf->xb, yb); + } + VERTEX(edge, BELOW, RIGHT, xb, yb); + edge->outp[ABOVE]= NULL; + break; + case IMX: + VERTEX(edge, BELOW, LEFT, xb, yb); + edge->outp[ABOVE]= NULL; + cft= IMX; + break; case IMM: - VERTEX(edge, BELOW, LEFT, xb, yb); - edge->outp[ABOVE]= cf->outp[ABOVE]; - if (xb != cf->xb) - VERTEX(cf, ABOVE, RIGHT, xb, yb); - cf= edge; - break; - case EMM: - VERTEX(edge, BELOW, RIGHT, xb, yb); - edge->outp[ABOVE]= NULL; - new_tristrip(&tlist, edge, xb, yb); - cf= edge; - break; - case LED: - if (edge->bot.y == yb) - VERTEX(edge, BELOW, LEFT, xb, yb); - edge->outp[ABOVE]= edge->outp[BELOW]; - cf= edge; - cft= LED; - break; - case RED: - edge->outp[ABOVE]= cf->outp[ABOVE]; - if (cft == LED) - { - if (cf->bot.y == yb) - { - VERTEX(edge, BELOW, RIGHT, xb, yb); - } - else - { - if (edge->bot.y == yb) + VERTEX(edge, BELOW, LEFT, xb, yb); + edge->outp[ABOVE]= cf->outp[ABOVE]; + if (xb != cf->xb) + VERTEX(cf, ABOVE, RIGHT, xb, yb); + cf= edge; + break; + case EMM: + VERTEX(edge, BELOW, RIGHT, xb, yb); + edge->outp[ABOVE]= NULL; + new_tristrip(&tlist, edge, xb, yb); + cf= edge; + break; + case LED: + if (edge->bot.y == yb) + VERTEX(edge, BELOW, LEFT, xb, yb); + edge->outp[ABOVE]= edge->outp[BELOW]; + cf= edge; + cft= LED; + break; + case RED: + edge->outp[ABOVE]= cf->outp[ABOVE]; + if (cft == LED) + { + if (cf->bot.y == yb) + { + VERTEX(edge, BELOW, RIGHT, xb, yb); + } + else + { + if (edge->bot.y == yb) + { + VERTEX(cf, BELOW, LEFT, cf->xb, yb); + VERTEX(edge, BELOW, RIGHT, xb, yb); + } + } + } + else { - VERTEX(cf, BELOW, LEFT, cf->xb, yb); - VERTEX(edge, BELOW, RIGHT, xb, yb); + VERTEX(edge, BELOW, RIGHT, xb, yb); + VERTEX(edge, ABOVE, RIGHT, xb, yb); } - } - } - else - { - VERTEX(edge, BELOW, RIGHT, xb, yb); - VERTEX(edge, ABOVE, RIGHT, xb, yb); - } - cf= NULL; - break; - default: - break; - } /* End of switch */ - } /* End of contributing conditional */ - } /* End of edge exists conditional */ - } /* End of AET loop */ - - /* Delete terminating edges from the AET, otherwise compute xt */ - for (edge= aet; edge; edge= edge->next) - { - if (edge->top.y == yb) - { - prev_edge= edge->prev; - next_edge= edge->next; - if (prev_edge) - prev_edge->next= next_edge; - else - aet= next_edge; - if (next_edge) - next_edge->prev= prev_edge; - - /* Copy bundle head state to the adjacent tail edge if required */ - if ((edge->bstate[BELOW] == BUNDLE_HEAD) && prev_edge) + cf= NULL; + break; + default: + break; + } /* End of switch */ + } /* End of contributing conditional */ + } /* End of edge exists conditional */ + } /* End of AET loop */ + + /* Delete terminating edges from the AET, otherwise compute xt */ + for (edge= aet; edge; edge= edge->next) + { + if (edge->top.y == yb) + { + prev_edge= edge->prev; + next_edge= edge->next; + if (prev_edge) + prev_edge->next= next_edge; + else + aet= next_edge; + if (next_edge) + next_edge->prev= prev_edge; + + /* Copy bundle head state to the adjacent tail edge if required */ + if ((edge->bstate[BELOW] == BUNDLE_HEAD) && prev_edge) { - if (prev_edge->bstate[BELOW] == BUNDLE_TAIL) - { - prev_edge->outp[BELOW]= edge->outp[BELOW]; - prev_edge->bstate[BELOW]= UNBUNDLED; - if (prev_edge->prev) - if (prev_edge->prev->bstate[BELOW] == BUNDLE_TAIL) - prev_edge->bstate[BELOW]= BUNDLE_HEAD; + if (prev_edge->bstate[BELOW] == BUNDLE_TAIL) + { + prev_edge->outp[BELOW]= edge->outp[BELOW]; + prev_edge->bstate[BELOW]= UNBUNDLED; + if (prev_edge->prev) + if (prev_edge->prev->bstate[BELOW] == BUNDLE_TAIL) + prev_edge->bstate[BELOW]= BUNDLE_HEAD; + } + } + } + else + { + if (edge->top.y == yt) + edge->xt= edge->top.x; + else + edge->xt= edge->bot.x + edge->dx * (yt - edge->bot.y); } } - } - else - { - if (edge->top.y == yt) - edge->xt= edge->top.x; - else - edge->xt= edge->bot.x + edge->dx * (yt - edge->bot.y); - } - } - - if (scanbeam < sbt_entries) - { - /* === SCANBEAM INTERIOR PROCESSING ============================== */ - - build_intersection_table(&it, aet, dy); - - /* Process each node in the intersection table */ - for (intersect= it; intersect; intersect= intersect->next) - { - e0= intersect->ie[0]; - e1= intersect->ie[1]; - - /* Only generate output for contributing intersections */ - if ((e0->bundle[ABOVE][CLIP] || e0->bundle[ABOVE][SUBJ]) - && (e1->bundle[ABOVE][CLIP] || e1->bundle[ABOVE][SUBJ])) + + if (scanbeam < sbt_entries) + { + /* === SCANBEAM INTERIOR PROCESSING ============================== */ + + build_intersection_table(&it, aet, dy); + + /* Process each node in the intersection table */ + for (intersect= it; intersect; intersect= intersect->next) + { + e0= intersect->ie[0]; + e1= intersect->ie[1]; + + /* Only generate output for contributing intersections */ + if ((e0->bundle[ABOVE][CLIP] || e0->bundle[ABOVE][SUBJ]) + && (e1->bundle[ABOVE][CLIP] || e1->bundle[ABOVE][SUBJ])) { - p= e0->outp[ABOVE]; - q= e1->outp[ABOVE]; - ix= intersect->point.x; - iy= intersect->point.y + yb; - - in[CLIP]= ( e0->bundle[ABOVE][CLIP] && !e0->bside[CLIP]) - || ( e1->bundle[ABOVE][CLIP] && e1->bside[CLIP]) - || (!e0->bundle[ABOVE][CLIP] && !e1->bundle[ABOVE][CLIP] - && e0->bside[CLIP] && e1->bside[CLIP]); - in[SUBJ]= ( e0->bundle[ABOVE][SUBJ] && !e0->bside[SUBJ]) - || ( e1->bundle[ABOVE][SUBJ] && e1->bside[SUBJ]) - || (!e0->bundle[ABOVE][SUBJ] && !e1->bundle[ABOVE][SUBJ] - && e0->bside[SUBJ] && e1->bside[SUBJ]); - - /* Determine quadrant occupancies */ - switch (op) - { - case GPC_DIFF: - case GPC_INT: - tr= (in[CLIP]) - && (in[SUBJ]); - tl= (in[CLIP] ^ e1->bundle[ABOVE][CLIP]) - && (in[SUBJ] ^ e1->bundle[ABOVE][SUBJ]); - br= (in[CLIP] ^ e0->bundle[ABOVE][CLIP]) - && (in[SUBJ] ^ e0->bundle[ABOVE][SUBJ]); - bl= (in[CLIP] ^ e1->bundle[ABOVE][CLIP] ^ e0->bundle[ABOVE][CLIP]) - && (in[SUBJ] ^ e1->bundle[ABOVE][SUBJ] ^ e0->bundle[ABOVE][SUBJ]); - break; - case GPC_XOR: - tr= (in[CLIP]) - ^ (in[SUBJ]); - tl= (in[CLIP] ^ e1->bundle[ABOVE][CLIP]) - ^ (in[SUBJ] ^ e1->bundle[ABOVE][SUBJ]); - br= (in[CLIP] ^ e0->bundle[ABOVE][CLIP]) - ^ (in[SUBJ] ^ e0->bundle[ABOVE][SUBJ]); - bl= (in[CLIP] ^ e1->bundle[ABOVE][CLIP] ^ e0->bundle[ABOVE][CLIP]) - ^ (in[SUBJ] ^ e1->bundle[ABOVE][SUBJ] ^ e0->bundle[ABOVE][SUBJ]); - break; - case GPC_UNION: - tr= (in[CLIP]) - || (in[SUBJ]); - tl= (in[CLIP] ^ e1->bundle[ABOVE][CLIP]) - || (in[SUBJ] ^ e1->bundle[ABOVE][SUBJ]); - br= (in[CLIP] ^ e0->bundle[ABOVE][CLIP]) - || (in[SUBJ] ^ e0->bundle[ABOVE][SUBJ]); - bl= (in[CLIP] ^ e1->bundle[ABOVE][CLIP] ^ e0->bundle[ABOVE][CLIP]) - || (in[SUBJ] ^ e1->bundle[ABOVE][SUBJ] ^ e0->bundle[ABOVE][SUBJ]); - break; - } - - vclass= tr + (tl << 1) + (br << 2) + (bl << 3); - - switch (vclass) - { - case EMN: - new_tristrip(&tlist, e1, ix, iy); - e0->outp[ABOVE]= e1->outp[ABOVE]; - break; - case ERI: - if (p) - { - P_EDGE(prev_edge, e0, ABOVE, px, iy); - VERTEX(prev_edge, ABOVE, LEFT, px, iy); - VERTEX(e0, ABOVE, RIGHT, ix, iy); - e1->outp[ABOVE]= e0->outp[ABOVE]; - e0->outp[ABOVE]= NULL; - } - break; - case ELI: - if (q) - { - N_EDGE(next_edge, e1, ABOVE, nx, iy); - VERTEX(e1, ABOVE, LEFT, ix, iy); - VERTEX(next_edge, ABOVE, RIGHT, nx, iy); - e0->outp[ABOVE]= e1->outp[ABOVE]; - e1->outp[ABOVE]= NULL; - } - break; - case EMX: - if (p && q) - { - VERTEX(e0, ABOVE, LEFT, ix, iy); - e0->outp[ABOVE]= NULL; - e1->outp[ABOVE]= NULL; - } - break; - case IMN: - P_EDGE(prev_edge, e0, ABOVE, px, iy); - VERTEX(prev_edge, ABOVE, LEFT, px, iy); - N_EDGE(next_edge, e1, ABOVE, nx, iy); - VERTEX(next_edge, ABOVE, RIGHT, nx, iy); - new_tristrip(&tlist, prev_edge, px, iy); - e1->outp[ABOVE]= prev_edge->outp[ABOVE]; - VERTEX(e1, ABOVE, RIGHT, ix, iy); - new_tristrip(&tlist, e0, ix, iy); - next_edge->outp[ABOVE]= e0->outp[ABOVE]; - VERTEX(next_edge, ABOVE, RIGHT, nx, iy); - break; - case ILI: - if (p) - { - VERTEX(e0, ABOVE, LEFT, ix, iy); - N_EDGE(next_edge, e1, ABOVE, nx, iy); - VERTEX(next_edge, ABOVE, RIGHT, nx, iy); - e1->outp[ABOVE]= e0->outp[ABOVE]; - e0->outp[ABOVE]= NULL; - } - break; - case IRI: - if (q) - { - VERTEX(e1, ABOVE, RIGHT, ix, iy); - P_EDGE(prev_edge, e0, ABOVE, px, iy); - VERTEX(prev_edge, ABOVE, LEFT, px, iy); - e0->outp[ABOVE]= e1->outp[ABOVE]; - e1->outp[ABOVE]= NULL; - } - break; - case IMX: - if (p && q) - { - VERTEX(e0, ABOVE, RIGHT, ix, iy); - VERTEX(e1, ABOVE, LEFT, ix, iy); - e0->outp[ABOVE]= NULL; - e1->outp[ABOVE]= NULL; - P_EDGE(prev_edge, e0, ABOVE, px, iy); - VERTEX(prev_edge, ABOVE, LEFT, px, iy); - new_tristrip(&tlist, prev_edge, px, iy); - N_EDGE(next_edge, e1, ABOVE, nx, iy); - VERTEX(next_edge, ABOVE, RIGHT, nx, iy); - next_edge->outp[ABOVE]= prev_edge->outp[ABOVE]; - VERTEX(next_edge, ABOVE, RIGHT, nx, iy); - } - break; - case IMM: - if (p && q) - { - VERTEX(e0, ABOVE, RIGHT, ix, iy); - VERTEX(e1, ABOVE, LEFT, ix, iy); - P_EDGE(prev_edge, e0, ABOVE, px, iy); - VERTEX(prev_edge, ABOVE, LEFT, px, iy); - new_tristrip(&tlist, prev_edge, px, iy); - N_EDGE(next_edge, e1, ABOVE, nx, iy); - VERTEX(next_edge, ABOVE, RIGHT, nx, iy); - e1->outp[ABOVE]= prev_edge->outp[ABOVE]; - VERTEX(e1, ABOVE, RIGHT, ix, iy); - new_tristrip(&tlist, e0, ix, iy); - next_edge->outp[ABOVE]= e0->outp[ABOVE]; - VERTEX(next_edge, ABOVE, RIGHT, nx, iy); - } - break; - case EMM: - if (p && q) - { - VERTEX(e0, ABOVE, LEFT, ix, iy); - new_tristrip(&tlist, e1, ix, iy); - e0->outp[ABOVE]= e1->outp[ABOVE]; - } - break; - default: - break; - } /* End of switch */ + p= e0->outp[ABOVE]; + q= e1->outp[ABOVE]; + ix= intersect->point.x; + iy= intersect->point.y + yb; + + in[CLIP]= ( e0->bundle[ABOVE][CLIP] && !e0->bside[CLIP]) + || ( e1->bundle[ABOVE][CLIP] && e1->bside[CLIP]) + || (!e0->bundle[ABOVE][CLIP] && !e1->bundle[ABOVE][CLIP] + && e0->bside[CLIP] && e1->bside[CLIP]); + in[SUBJ]= ( e0->bundle[ABOVE][SUBJ] && !e0->bside[SUBJ]) + || ( e1->bundle[ABOVE][SUBJ] && e1->bside[SUBJ]) + || (!e0->bundle[ABOVE][SUBJ] && !e1->bundle[ABOVE][SUBJ] + && e0->bside[SUBJ] && e1->bside[SUBJ]); + + /* Determine quadrant occupancies */ + switch (op) + { + case GPC_DIFF: + case GPC_INT: + tr= (in[CLIP]) + && (in[SUBJ]); + tl= (in[CLIP] ^ e1->bundle[ABOVE][CLIP]) + && (in[SUBJ] ^ e1->bundle[ABOVE][SUBJ]); + br= (in[CLIP] ^ e0->bundle[ABOVE][CLIP]) + && (in[SUBJ] ^ e0->bundle[ABOVE][SUBJ]); + bl= (in[CLIP] ^ e1->bundle[ABOVE][CLIP] ^ e0->bundle[ABOVE][CLIP]) + && (in[SUBJ] ^ e1->bundle[ABOVE][SUBJ] ^ e0->bundle[ABOVE][SUBJ]); + break; + case GPC_XOR: + tr= (in[CLIP]) + ^ (in[SUBJ]); + tl= (in[CLIP] ^ e1->bundle[ABOVE][CLIP]) + ^ (in[SUBJ] ^ e1->bundle[ABOVE][SUBJ]); + br= (in[CLIP] ^ e0->bundle[ABOVE][CLIP]) + ^ (in[SUBJ] ^ e0->bundle[ABOVE][SUBJ]); + bl= (in[CLIP] ^ e1->bundle[ABOVE][CLIP] ^ e0->bundle[ABOVE][CLIP]) + ^ (in[SUBJ] ^ e1->bundle[ABOVE][SUBJ] ^ e0->bundle[ABOVE][SUBJ]); + break; + case GPC_UNION: + tr= (in[CLIP]) + || (in[SUBJ]); + tl= (in[CLIP] ^ e1->bundle[ABOVE][CLIP]) + || (in[SUBJ] ^ e1->bundle[ABOVE][SUBJ]); + br= (in[CLIP] ^ e0->bundle[ABOVE][CLIP]) + || (in[SUBJ] ^ e0->bundle[ABOVE][SUBJ]); + bl= (in[CLIP] ^ e1->bundle[ABOVE][CLIP] ^ e0->bundle[ABOVE][CLIP]) + || (in[SUBJ] ^ e1->bundle[ABOVE][SUBJ] ^ e0->bundle[ABOVE][SUBJ]); + break; + } + + vclass= tr + (tl << 1) + (br << 2) + (bl << 3); + + switch (vclass) + { + case EMN: + new_tristrip(&tlist, e1, ix, iy); + e0->outp[ABOVE]= e1->outp[ABOVE]; + break; + case ERI: + if (p) + { + P_EDGE(prev_edge, e0, ABOVE, px, iy); + VERTEX(prev_edge, ABOVE, LEFT, px, iy); + VERTEX(e0, ABOVE, RIGHT, ix, iy); + e1->outp[ABOVE]= e0->outp[ABOVE]; + e0->outp[ABOVE]= NULL; + } + break; + case ELI: + if (q) + { + N_EDGE(next_edge, e1, ABOVE, nx, iy); + VERTEX(e1, ABOVE, LEFT, ix, iy); + VERTEX(next_edge, ABOVE, RIGHT, nx, iy); + e0->outp[ABOVE]= e1->outp[ABOVE]; + e1->outp[ABOVE]= NULL; + } + break; + case EMX: + if (p && q) + { + VERTEX(e0, ABOVE, LEFT, ix, iy); + e0->outp[ABOVE]= NULL; + e1->outp[ABOVE]= NULL; + } + break; + case IMN: + P_EDGE(prev_edge, e0, ABOVE, px, iy); + VERTEX(prev_edge, ABOVE, LEFT, px, iy); + N_EDGE(next_edge, e1, ABOVE, nx, iy); + VERTEX(next_edge, ABOVE, RIGHT, nx, iy); + new_tristrip(&tlist, prev_edge, px, iy); + e1->outp[ABOVE]= prev_edge->outp[ABOVE]; + VERTEX(e1, ABOVE, RIGHT, ix, iy); + new_tristrip(&tlist, e0, ix, iy); + next_edge->outp[ABOVE]= e0->outp[ABOVE]; + VERTEX(next_edge, ABOVE, RIGHT, nx, iy); + break; + case ILI: + if (p) + { + VERTEX(e0, ABOVE, LEFT, ix, iy); + N_EDGE(next_edge, e1, ABOVE, nx, iy); + VERTEX(next_edge, ABOVE, RIGHT, nx, iy); + e1->outp[ABOVE]= e0->outp[ABOVE]; + e0->outp[ABOVE]= NULL; + } + break; + case IRI: + if (q) + { + VERTEX(e1, ABOVE, RIGHT, ix, iy); + P_EDGE(prev_edge, e0, ABOVE, px, iy); + VERTEX(prev_edge, ABOVE, LEFT, px, iy); + e0->outp[ABOVE]= e1->outp[ABOVE]; + e1->outp[ABOVE]= NULL; + } + break; + case IMX: + if (p && q) + { + VERTEX(e0, ABOVE, RIGHT, ix, iy); + VERTEX(e1, ABOVE, LEFT, ix, iy); + e0->outp[ABOVE]= NULL; + e1->outp[ABOVE]= NULL; + P_EDGE(prev_edge, e0, ABOVE, px, iy); + VERTEX(prev_edge, ABOVE, LEFT, px, iy); + new_tristrip(&tlist, prev_edge, px, iy); + N_EDGE(next_edge, e1, ABOVE, nx, iy); + VERTEX(next_edge, ABOVE, RIGHT, nx, iy); + next_edge->outp[ABOVE]= prev_edge->outp[ABOVE]; + VERTEX(next_edge, ABOVE, RIGHT, nx, iy); + } + break; + case IMM: + if (p && q) + { + VERTEX(e0, ABOVE, RIGHT, ix, iy); + VERTEX(e1, ABOVE, LEFT, ix, iy); + P_EDGE(prev_edge, e0, ABOVE, px, iy); + VERTEX(prev_edge, ABOVE, LEFT, px, iy); + new_tristrip(&tlist, prev_edge, px, iy); + N_EDGE(next_edge, e1, ABOVE, nx, iy); + VERTEX(next_edge, ABOVE, RIGHT, nx, iy); + e1->outp[ABOVE]= prev_edge->outp[ABOVE]; + VERTEX(e1, ABOVE, RIGHT, ix, iy); + new_tristrip(&tlist, e0, ix, iy); + next_edge->outp[ABOVE]= e0->outp[ABOVE]; + VERTEX(next_edge, ABOVE, RIGHT, nx, iy); + } + break; + case EMM: + if (p && q) + { + VERTEX(e0, ABOVE, LEFT, ix, iy); + new_tristrip(&tlist, e1, ix, iy); + e0->outp[ABOVE]= e1->outp[ABOVE]; + } + break; + default: + break; + } /* End of switch */ } /* End of contributing intersection conditional */ - /* Swap bundle sides in response to edge crossing */ - if (e0->bundle[ABOVE][CLIP]) + /* Swap bundle sides in response to edge crossing */ + if (e0->bundle[ABOVE][CLIP]) e1->bside[CLIP]= !e1->bside[CLIP]; - if (e1->bundle[ABOVE][CLIP]) + if (e1->bundle[ABOVE][CLIP]) e0->bside[CLIP]= !e0->bside[CLIP]; - if (e0->bundle[ABOVE][SUBJ]) + if (e0->bundle[ABOVE][SUBJ]) e1->bside[SUBJ]= !e1->bside[SUBJ]; - if (e1->bundle[ABOVE][SUBJ]) + if (e1->bundle[ABOVE][SUBJ]) e0->bside[SUBJ]= !e0->bside[SUBJ]; - /* Swap e0 and e1 bundles in the AET */ - prev_edge= e0->prev; - next_edge= e1->next; - if (e1->next) - e1->next->prev= e0; - - if (e0->bstate[ABOVE] == BUNDLE_HEAD) - { - search= TRUE; - while (search) - { - prev_edge= prev_edge->prev; - if (prev_edge) - { - if (prev_edge->bundle[ABOVE][CLIP] - || prev_edge->bundle[ABOVE][SUBJ] - || (prev_edge->bstate[ABOVE] == BUNDLE_HEAD)) - search= FALSE; - } - else - search= FALSE; - } - } - if (!prev_edge) - { - e1->next= aet; - aet= e0->next; - } - else - { - e1->next= prev_edge->next; - prev_edge->next= e0->next; - } - e0->next->prev= prev_edge; - e1->next->prev= e1; - e0->next= next_edge; - } /* End of IT loop*/ - - /* Prepare for next scanbeam */ - for (edge= aet; edge; edge= next_edge) - { - next_edge= edge->next; - succ_edge= edge->succ; - - if ((edge->top.y == yt) && succ_edge) - { - /* Replace AET edge by its successor */ - succ_edge->outp[BELOW]= edge->outp[ABOVE]; - succ_edge->bstate[BELOW]= edge->bstate[ABOVE]; - succ_edge->bundle[BELOW][CLIP]= edge->bundle[ABOVE][CLIP]; - succ_edge->bundle[BELOW][SUBJ]= edge->bundle[ABOVE][SUBJ]; - prev_edge= edge->prev; - if (prev_edge) - prev_edge->next= succ_edge; - else - aet= succ_edge; - if (next_edge) - next_edge->prev= succ_edge; - succ_edge->prev= prev_edge; - succ_edge->next= next_edge; - } - else - { - /* Update this edge */ - edge->outp[BELOW]= edge->outp[ABOVE]; - edge->bstate[BELOW]= edge->bstate[ABOVE]; - edge->bundle[BELOW][CLIP]= edge->bundle[ABOVE][CLIP]; - edge->bundle[BELOW][SUBJ]= edge->bundle[ABOVE][SUBJ]; - edge->xb= edge->xt; - } - edge->outp[ABOVE]= NULL; - } - } + /* Swap e0 and e1 bundles in the AET */ + prev_edge= e0->prev; + next_edge= e1->next; + if (e1->next) + e1->next->prev= e0; + + if (e0->bstate[ABOVE] == BUNDLE_HEAD) + { + search= TRUE; + while (search) + { + prev_edge= prev_edge->prev; + if (prev_edge) + { + if (prev_edge->bundle[ABOVE][CLIP] + || prev_edge->bundle[ABOVE][SUBJ] + || (prev_edge->bstate[ABOVE] == BUNDLE_HEAD)) + search= FALSE; + } + else + search= FALSE; + } + } + if (!prev_edge) + { + e1->next= aet; + aet= e0->next; + } + else + { + e1->next= prev_edge->next; + prev_edge->next= e0->next; + } + e0->next->prev= prev_edge; + e1->next->prev= e1; + e0->next= next_edge; + } /* End of IT loop*/ + + /* Prepare for next scanbeam */ + for (edge= aet; edge; edge= next_edge) + { + next_edge= edge->next; + succ_edge= edge->succ; + + if ((edge->top.y == yt) && succ_edge) + { + /* Replace AET edge by its successor */ + succ_edge->outp[BELOW]= edge->outp[ABOVE]; + succ_edge->bstate[BELOW]= edge->bstate[ABOVE]; + succ_edge->bundle[BELOW][CLIP]= edge->bundle[ABOVE][CLIP]; + succ_edge->bundle[BELOW][SUBJ]= edge->bundle[ABOVE][SUBJ]; + prev_edge= edge->prev; + if (prev_edge) + prev_edge->next= succ_edge; + else + aet= succ_edge; + if (next_edge) + next_edge->prev= succ_edge; + succ_edge->prev= prev_edge; + succ_edge->next= next_edge; + } + else + { + /* Update this edge */ + edge->outp[BELOW]= edge->outp[ABOVE]; + edge->bstate[BELOW]= edge->bstate[ABOVE]; + edge->bundle[BELOW][CLIP]= edge->bundle[ABOVE][CLIP]; + edge->bundle[BELOW][SUBJ]= edge->bundle[ABOVE][SUBJ]; + edge->xb= edge->xt; + } + edge->outp[ABOVE]= NULL; + } + } } /* === END OF SCANBEAM PROCESSING ================================== */ /* Generate result tristrip from tlist */ @@ -2468,70 +2463,70 @@ void gpc_tristrip_clip(gpc_op op, gpc_polygon *subj, gpc_polygon *clip, result->num_strips= count_tristrips(tlist); if (result->num_strips > 0) { - MALLOC(result->strip, result->num_strips * sizeof(gpc_vertex_list), - "tristrip list creation", gpc_vertex_list); - - s= 0; - for (tn= tlist; tn; tn= tnn) - { - tnn= tn->next; - - if (tn->active > 2) - { - /* Valid tristrip: copy the vertices and free the heap */ - result->strip[s].num_vertices= tn->active; - MALLOC(result->strip[s].vertex, tn->active * sizeof(gpc_vertex), - "tristrip creation", gpc_vertex); - v= 0; - if (INVERT_TRISTRIPS) - { - lt= tn->v[RIGHT]; - rt= tn->v[LEFT]; - } - else - { - lt= tn->v[LEFT]; - rt= tn->v[RIGHT]; - } - while (lt || rt) - { - if (lt) - { - ltn= lt->next; - result->strip[s].vertex[v].x= lt->x; - result->strip[s].vertex[v].y= lt->y; - v++; - FREE(lt); - lt= ltn; - } - if (rt) - { - rtn= rt->next; - result->strip[s].vertex[v].x= rt->x; - result->strip[s].vertex[v].y= rt->y; - v++; - FREE(rt); - rt= rtn; - } - } - s++; - } - else - { - /* Invalid tristrip: just free the heap */ - for (lt= tn->v[LEFT]; lt; lt= ltn) - { - ltn= lt->next; - FREE(lt); - } - for (rt= tn->v[RIGHT]; rt; rt=rtn) - { - rtn= rt->next; - FREE(rt); - } - } - FREE(tn); - } + MALLOC(result->strip, result->num_strips * sizeof(gpc_vertex_list), + "tristrip list creation", gpc_vertex_list); + + s= 0; + for (tn= tlist; tn; tn= tnn) + { + tnn= tn->next; + + if (tn->active > 2) + { + /* Valid tristrip: copy the vertices and free the heap */ + result->strip[s].num_vertices= tn->active; + MALLOC(result->strip[s].vertex, tn->active * sizeof(gpc_vertex), + "tristrip creation", gpc_vertex); + v= 0; + if (INVERT_TRISTRIPS) + { + lt= tn->v[RIGHT]; + rt= tn->v[LEFT]; + } + else + { + lt= tn->v[LEFT]; + rt= tn->v[RIGHT]; + } + while (lt || rt) + { + if (lt) + { + ltn= lt->next; + result->strip[s].vertex[v].x= lt->x; + result->strip[s].vertex[v].y= lt->y; + v++; + FREE(lt); + lt= ltn; + } + if (rt) + { + rtn= rt->next; + result->strip[s].vertex[v].x= rt->x; + result->strip[s].vertex[v].y= rt->y; + v++; + FREE(rt); + rt= rtn; + } + } + s++; + } + else + { + /* Invalid tristrip: just free the heap */ + for (lt= tn->v[LEFT]; lt; lt= ltn) + { + ltn= lt->next; + FREE(lt); + } + for (rt= tn->v[RIGHT]; rt; rt=rtn) + { + rtn= rt->next; + FREE(rt); + } + } + FREE(tn); + } } /* Tidy up */ @@ -2544,6 +2539,6 @@ void gpc_tristrip_clip(gpc_op op, gpc_polygon *subj, gpc_polygon *clip, /* =========================================================================== - End of file: gpc.c + End of file: gpc.c =========================================================================== */ diff --git a/octovis/src/extern/QGLViewer/VRender/gpc.h b/octovis/src/extern/QGLViewer/VRender/gpc.h index 063901db..07841c65 100644 --- a/octovis/src/extern/QGLViewer/VRender/gpc.h +++ b/octovis/src/extern/QGLViewer/VRender/gpc.h @@ -22,9 +22,9 @@ /**************************************************************************** - Copyright (C) 2002-2013 Gilles Debunne. All rights reserved. + Copyright (C) 2002-2014 Gilles Debunne. All rights reserved. - This file is part of the QGLViewer library version 2.4.0. + This file is part of the QGLViewer library version 2.6.3. http://www.libqglviewer.com - contact@libqglviewer.com @@ -47,8 +47,8 @@ Project: Generic Polygon Clipper - A new algorithm for calculating the difference, intersection, - exclusive-or or union of arbitrary polygon sets. + A new algorithm for calculating the difference, intersection, + exclusive-or or union of arbitrary polygon sets. File: gpc.h Author: Alan Murta (email: gpc@cs.man.ac.uk) @@ -56,20 +56,20 @@ Version: 2.32 Date: 17th December 2004 Copyright: (C) 1997-2004, Advanced Interfaces Group, - University of Manchester. + University of Manchester. - This software is free for non-commercial use. It may be copied, - modified, and redistributed provided that this copyright notice - is preserved on all copies. The intellectual property rights of - the algorithms used reside with the University of Manchester - Advanced Interfaces Group. + This software is free for non-commercial use. It may be copied, + modified, and redistributed provided that this copyright notice + is preserved on all copies. The intellectual property rights of + the algorithms used reside with the University of Manchester + Advanced Interfaces Group. - You may not use this software, in whole or in part, in support - of any commercial product without the express consent of the - author. + You may not use this software, in whole or in part, in support + of any commercial product without the express consent of the + author. - There is no warranty or other guarantee of fitness of this - software for any purpose. It is provided solely "as is". + There is no warranty or other guarantee of fitness of this + software for any purpose. It is provided solely "as is". =========================================================================== */ @@ -82,7 +82,7 @@ Copyright: (C) 1997-2004, Advanced Interfaces Group, /* =========================================================================== - Constants + Constants =========================================================================== */ @@ -96,7 +96,7 @@ Copyright: (C) 1997-2004, Advanced Interfaces Group, /* =========================================================================== - Public Data Types + Public Data Types =========================================================================== */ @@ -116,54 +116,54 @@ typedef struct /* Polygon vertex structure */ typedef struct /* Vertex list structure */ { - int num_vertices; /* Number of vertices in list */ + long num_vertices; /* Number of vertices in list */ gpc_vertex *vertex; /* Vertex array pointer */ } gpc_vertex_list; typedef struct /* Polygon set structure */ { - int num_contours; /* Number of contours in polygon */ + unsigned long num_contours; /* Number of contours in polygon */ int *hole; /* Hole / external contour flags */ gpc_vertex_list *contour; /* Contour array pointer */ } gpc_polygon; typedef struct /* Tristrip set structure */ { - int num_strips; /* Number of tristrips */ + unsigned long num_strips; /* Number of tristrips */ gpc_vertex_list *strip; /* Tristrip array pointer */ } gpc_tristrip; /* =========================================================================== - Public Function Prototypes + Public Function Prototypes =========================================================================== */ void gpc_read_polygon (FILE *infile_ptr, - int read_hole_flags, - gpc_polygon *polygon); + int read_hole_flags, + gpc_polygon *polygon); void gpc_write_polygon (FILE *outfile_ptr, - int write_hole_flags, - gpc_polygon *polygon); + int write_hole_flags, + gpc_polygon *polygon); void gpc_add_contour (gpc_polygon *polygon, - gpc_vertex_list *contour, - int hole); + gpc_vertex_list *contour, + int hole); void gpc_polygon_clip (gpc_op set_operation, - gpc_polygon *subject_polygon, - gpc_polygon *clip_polygon, - gpc_polygon *result_polygon); + gpc_polygon *subject_polygon, + gpc_polygon *clip_polygon, + gpc_polygon *result_polygon); void gpc_tristrip_clip (gpc_op set_operation, - gpc_polygon *subject_polygon, - gpc_polygon *clip_polygon, - gpc_tristrip *result_tristrip); + gpc_polygon *subject_polygon, + gpc_polygon *clip_polygon, + gpc_tristrip *result_tristrip); void gpc_polygon_to_tristrip (gpc_polygon *polygon, - gpc_tristrip *tristrip); + gpc_tristrip *tristrip); void gpc_free_polygon (gpc_polygon *polygon); @@ -174,6 +174,6 @@ void gpc_free_tristrip (gpc_tristrip *tristrip); /* =========================================================================== - End of file: gpc.h + End of file: gpc.h =========================================================================== */ diff --git a/octovis/src/extern/QGLViewer/VRenderInterface.Qt3.ui b/octovis/src/extern/QGLViewer/VRenderInterface.Qt3.ui deleted file mode 100644 index b185267c..00000000 --- a/octovis/src/extern/QGLViewer/VRenderInterface.Qt3.ui +++ /dev/null @@ -1,211 +0,0 @@ - -VRenderInterface - - - VRenderInterface - - - - 0 - 0 - 298 - 245 - - - - Vectorial rendering options - - - - unnamed - - - 5 - - - 6 - - - - includeHidden - - - Include hidden parts - - - Hidden polygons are also included in the output (usually twice bigger) - - - - - cullBackFaces - - - Cull back faces - - - Back faces (non clockwise point ordering) are removed from the output - - - - - blackAndWhite - - - Black and white - - - Black and white rendering - - - - - colorBackground - - - Color background - - - Use current background color instead of white - - - - - tightenBBox - - - Tighten bounding box - - - Fit output bounding box to current display - - - - - layout3 - - - - unnamed - - - - sortLabel - - - Sort method: - - - Polygon depth sorting method - - - - - - No sorting - - - - - BSP - - - - - Topological - - - - - Advanced topological - - - - sortMethod - - - 3 - - - Polygon depth sorting method - - - - - - - spacer1 - - - Vertical - - - Expanding - - - - 31 - 41 - - - - - - Layout4 - - - - unnamed - - - 0 - - - 6 - - - - SaveButton - - - Save - - - - - CancelButton - - - Cancel - - - - - - - - - SaveButton - clicked() - VRenderInterface - accept() - - - CancelButton - clicked() - VRenderInterface - reject() - - - - SaveButton - CancelButton - includeHidden - cullBackFaces - blackAndWhite - colorBackground - tightenBBox - sortMethod - - - diff --git a/octovis/src/extern/QGLViewer/VRenderInterface.ui b/octovis/src/extern/QGLViewer/VRenderInterface.ui index 99207422..e6e1a608 100644 --- a/octovis/src/extern/QGLViewer/VRenderInterface.ui +++ b/octovis/src/extern/QGLViewer/VRenderInterface.ui @@ -6,18 +6,24 @@ 0 0 - 306 - 191 + 309 + 211 Vectorial rendering options - - 6 + + 5 + + + 5 - + + 5 + + 5 @@ -72,10 +78,16 @@ - - 6 + + 11 - + + 11 + + + 11 + + 11 @@ -138,12 +150,6 @@ - - 6 - - - 0 - diff --git a/octovis/src/extern/QGLViewer/camera.cpp b/octovis/src/extern/QGLViewer/camera.cpp index 958c59b0..70dde8e3 100644 --- a/octovis/src/extern/QGLViewer/camera.cpp +++ b/octovis/src/extern/QGLViewer/camera.cpp @@ -1,8 +1,8 @@ /**************************************************************************** - Copyright (C) 2002-2013 Gilles Debunne. All rights reserved. + Copyright (C) 2002-2014 Gilles Debunne. All rights reserved. - This file is part of the QGLViewer library version 2.4.0. + This file is part of the QGLViewer library version 2.6.3. http://www.libqglviewer.com - contact@libqglviewer.com @@ -23,6 +23,7 @@ #include "domUtils.h" #include "camera.h" #include "qglviewer.h" +#include "manipulatedCameraFrame.h" using namespace std; using namespace qglviewer; @@ -35,47 +36,47 @@ using namespace qglviewer; See IODistance(), physicalDistanceToScreen(), physicalScreenWidth() and focusDistance() documentations for default stereo parameter values. */ Camera::Camera() - : fieldOfView_(M_PI/4.0f) + : frame_(NULL), fieldOfView_(M_PI/4.0), modelViewMatrixIsUpToDate_(false), projectionMatrixIsUpToDate_(false) { - // #CONNECTION# Camera copy constructor - interpolationKfi_ = new KeyFrameInterpolator; - // Requires the interpolationKfi_ - setFrame(new ManipulatedCameraFrame()); + // #CONNECTION# Camera copy constructor + interpolationKfi_ = new KeyFrameInterpolator; + // Requires the interpolationKfi_ + setFrame(new ManipulatedCameraFrame()); - // #CONNECTION# All these default values identical in initFromDOMElement. + // #CONNECTION# All these default values identical in initFromDOMElement. - // Requires fieldOfView() to define focusDistance() - setSceneRadius(1.0); + // Requires fieldOfView() to define focusDistance() + setSceneRadius(1.0); - // Initial value (only scaled after this) - orthoCoef_ = tan(fieldOfView()/2.0); + // Initial value (only scaled after this) + orthoCoef_ = tan(fieldOfView()/2.0); - // Also defines the revolveAroundPoint(), which changes orthoCoef_. Requires a frame(). - setSceneCenter(Vec(0.0, 0.0, 0.0)); + // Also defines the pivotPoint(), which changes orthoCoef_. Requires a frame(). + setSceneCenter(Vec(0.0, 0.0, 0.0)); - // Requires fieldOfView() when called with ORTHOGRAPHIC. Attention to projectionMatrix_ below. - setType(PERSPECTIVE); + // Requires fieldOfView() when called with ORTHOGRAPHIC. Attention to projectionMatrix_ below. + setType(PERSPECTIVE); - // #CONNECTION# initFromDOMElement default values - setZNearCoefficient(0.005f); - setZClippingCoefficient(sqrt(3.0)); + // #CONNECTION# initFromDOMElement default values + setZNearCoefficient(0.005); + setZClippingCoefficient(sqrt(3.0)); - // Dummy values - setScreenWidthAndHeight(600, 400); + // Dummy values + setScreenWidthAndHeight(600, 400); - // Stereo parameters - setIODistance(0.062f); - setPhysicalScreenWidth(0.5f); - // focusDistance is set from setFieldOfView() + // Stereo parameters + setIODistance(0.062); + setPhysicalScreenWidth(0.5); + // focusDistance is set from setFieldOfView() - // #CONNECTION# Camera copy constructor - for (unsigned short j=0; j<16; ++j) - { - modelViewMatrix_[j] = ((j%5 == 0) ? 1.0 : 0.0); - // #CONNECTION# computeProjectionMatrix() is lazy and assumes 0.0 almost everywhere. - projectionMatrix_[j] = 0.0; - } - computeProjectionMatrix(); + // #CONNECTION# Camera copy constructor + for (unsigned short j=0; j<16; ++j) + { + modelViewMatrix_[j] = ((j%5 == 0) ? 1.0 : 0.0); + // #CONNECTION# computeProjectionMatrix() is lazy and assumes 0.0 almost everywhere. + projectionMatrix_[j] = 0.0; + } + computeProjectionMatrix(); } /*! Virtual destructor. @@ -84,28 +85,28 @@ Camera::Camera() are shared). */ Camera::~Camera() { - delete frame_; - delete interpolationKfi_; + delete frame_; + delete interpolationKfi_; } /*! Copy constructor. Performs a deep copy using operator=(). */ Camera::Camera(const Camera& camera) - : QObject() + : QObject(), frame_(NULL) { - // #CONNECTION# Camera constructor - interpolationKfi_ = new KeyFrameInterpolator; - // Requires the interpolationKfi_ - setFrame(new ManipulatedCameraFrame()); + // #CONNECTION# Camera constructor + interpolationKfi_ = new KeyFrameInterpolator; + // Requires the interpolationKfi_ + setFrame(new ManipulatedCameraFrame(*camera.frame())); - for (unsigned short j=0; j<16; ++j) - { - modelViewMatrix_[j] = ((j%5 == 0) ? 1.0 : 0.0); - // #CONNECTION# computeProjectionMatrix() is lazy and assumes 0.0 almost everywhere. - projectionMatrix_[j] = 0.0; - } + for (unsigned short j=0; j<16; ++j) + { + modelViewMatrix_[j] = ((j%5 == 0) ? 1.0 : 0.0); + // #CONNECTION# computeProjectionMatrix() is lazy and assumes 0.0 almost everywhere. + projectionMatrix_[j] = 0.0; + } - (*this)=camera; + (*this)=camera; } /*! Equal operator. @@ -122,34 +123,35 @@ Camera::Camera(const Camera& camera) The same applies to sceneCenter() and sceneRadius(), if needed. */ Camera& Camera::operator=(const Camera& camera) { - setScreenWidthAndHeight(camera.screenWidth(), camera.screenHeight()); - setFieldOfView(camera.fieldOfView()); - setSceneRadius(camera.sceneRadius()); - setSceneCenter(camera.sceneCenter()); - setZNearCoefficient(camera.zNearCoefficient()); - setZClippingCoefficient(camera.zClippingCoefficient()); - setType(camera.type()); + setScreenWidthAndHeight(camera.screenWidth(), camera.screenHeight()); + setFieldOfView(camera.fieldOfView()); + setSceneRadius(camera.sceneRadius()); + setSceneCenter(camera.sceneCenter()); + setZNearCoefficient(camera.zNearCoefficient()); + setZClippingCoefficient(camera.zClippingCoefficient()); + setType(camera.type()); - // Stereo parameters - setIODistance(camera.IODistance()); - setFocusDistance(camera.focusDistance()); - setPhysicalScreenWidth(camera.physicalScreenWidth()); + // Stereo parameters + setIODistance(camera.IODistance()); + setFocusDistance(camera.focusDistance()); + setPhysicalScreenWidth(camera.physicalScreenWidth()); - orthoCoef_ = camera.orthoCoef_; + orthoCoef_ = camera.orthoCoef_; + projectionMatrixIsUpToDate_ = false; - // frame_ and interpolationKfi_ pointers are not shared. - frame_->setReferenceFrame(NULL); - frame_->setPosition(camera.position()); - frame_->setOrientation(camera.orientation()); + // frame_ and interpolationKfi_ pointers are not shared. + frame_->setReferenceFrame(NULL); + frame_->setPosition(camera.position()); + frame_->setOrientation(camera.orientation()); - interpolationKfi_->resetInterpolation(); + interpolationKfi_->resetInterpolation(); - kfi_ = camera.kfi_; + kfi_ = camera.kfi_; - computeProjectionMatrix(); - computeModelViewMatrix(); + computeProjectionMatrix(); + computeModelViewMatrix(); - return *this; + return *this; } /*! Sets Camera screenWidth() and screenHeight() (expressed in pixels). @@ -163,9 +165,10 @@ If your Camera is used without a QGLViewer (offscreen rendering, shadow maps), u instead to define the projection matrix. */ void Camera::setScreenWidthAndHeight(int width, int height) { - // Prevent negative and zero dimensions that would cause divisions by zero. + // Prevent negative and zero dimensions that would cause divisions by zero. screenWidth_ = width > 0 ? width : 1; screenHeight_ = height > 0 ? height : 1; + projectionMatrixIsUpToDate_ = false; } /*! Returns the near clipping plane distance used by the Camera projection matrix. @@ -183,7 +186,7 @@ void Camera::setScreenWidthAndHeight(int width, int height) In order to prevent negative or too small zNear() values (which would degrade the z precision), zNearCoefficient() is used when the Camera is inside the sceneRadius() sphere: \code - const float zMin = zNearCoefficient() * zClippingCoefficient() * sceneRadius(); + const qreal zMin = zNearCoefficient() * zClippingCoefficient() * sceneRadius(); if (zNear < zMin) zNear = zMin; // With an ORTHOGRAPHIC type, the value is simply clamped to 0.0 @@ -196,8 +199,8 @@ void Camera::setScreenWidthAndHeight(int width, int height) \code class myCamera :: public qglviewer::Camera { - virtual float Camera::zNear() const { return 0.001; }; - virtual float Camera::zFar() const { return 100.0; }; + virtual qreal Camera::zNear() const { return 0.001; }; + virtual qreal Camera::zFar() const { return 100.0; }; } \endcode @@ -205,19 +208,20 @@ void Camera::setScreenWidthAndHeight(int width, int height) \attention The value is always positive although the clipping plane is positioned at a negative z value in the Camera coordinate system. This follows the \c gluPerspective standard. */ -float Camera::zNear() const +qreal Camera::zNear() const { - float z = distanceToSceneCenter() - zClippingCoefficient()*sceneRadius(); + const qreal zNearScene = zClippingCoefficient() * sceneRadius(); + qreal z = distanceToSceneCenter() - zNearScene; - // Prevents negative or null zNear values. - const float zMin = zNearCoefficient() * zClippingCoefficient() * sceneRadius(); - if (z < zMin) - switch (type()) - { - case Camera::PERSPECTIVE : z = zMin; break; - case Camera::ORTHOGRAPHIC : z = 0.0; break; - } - return z; + // Prevents negative or null zNear values. + const qreal zMin = zNearCoefficient() * zNearScene; + if (z < zMin) + switch (type()) + { + case Camera::PERSPECTIVE : z = zMin; break; + case Camera::ORTHOGRAPHIC : z = 0.0; break; + } + return z; } /*! Returns the far clipping plane distance used by the Camera projection matrix. @@ -229,28 +233,40 @@ zFar = distanceToSceneCenter() + zClippingCoefficient()*sceneRadius(); \endcode See the zNear() documentation for details. */ -float Camera::zFar() const +qreal Camera::zFar() const { - return distanceToSceneCenter() + zClippingCoefficient()*sceneRadius(); + return distanceToSceneCenter() + zClippingCoefficient() * sceneRadius(); +} + + +/*! Sets the vertical fieldOfView() of the Camera (in radians). + +Note that focusDistance() is set to sceneRadius() / tan(fieldOfView()/2) by this method. */ +void Camera::setFieldOfView(qreal fov) { + fieldOfView_ = fov; + setFocusDistance(sceneRadius() / tan(fov/2.0)); + projectionMatrixIsUpToDate_ = false; } /*! Defines the Camera type(). -Changing the camera Type alters the viewport and the objects' size can be changed. This method garantees that the two frustum match in a plane normal to viewDirection(), passing through the Revolve Around Point (RAP). +Changing the camera Type alters the viewport and the objects' sizes can be changed. +This method garantees that the two frustum match in a plane normal to viewDirection(), passing through the pivotPoint(). -Prefix the type with \c Camera if needed, as in: -\code -camera()->setType(Camera::ORTHOGRAPHIC); -// or even qglviewer::Camera::ORTHOGRAPHIC if you do not use namespace +Prefix the type with \c Camera if needed, as in: +\code +camera()->setType(Camera::ORTHOGRAPHIC); +// or even qglviewer::Camera::ORTHOGRAPHIC if you do not use namespace \endcode */ void Camera::setType(Type type) { - // make ORTHOGRAPHIC frustum fit PERSPECTIVE (at least in plane normal to viewDirection(), passing - // through RAP). Done only when CHANGING type since orthoCoef_ may have been changed with a - // setRevolveAroundPoint() in the meantime. - if ( (type == Camera::ORTHOGRAPHIC) && (type_ == Camera::PERSPECTIVE) ) - orthoCoef_ = tan(fieldOfView()/2.0); - type_ = type; + // make ORTHOGRAPHIC frustum fit PERSPECTIVE (at least in plane normal to viewDirection(), passing + // through RAP). Done only when CHANGING type since orthoCoef_ may have been changed with a + // setPivotPoint() in the meantime. + if ( (type == Camera::ORTHOGRAPHIC) && (type_ == Camera::PERSPECTIVE) ) + orthoCoef_ = tan(fieldOfView()/2.0); + type_ = type; + projectionMatrixIsUpToDate_ = false; } /*! Sets the Camera frame(). @@ -268,18 +284,25 @@ A \c NULL \p mcf pointer will silently be ignored. The calling method is respons deleting the previous frame() pointer if needed in order to prevent memory leaks. */ void Camera::setFrame(ManipulatedCameraFrame* const mcf) { - if (!mcf) - return; + if (!mcf) + return; - frame_ = mcf; - interpolationKfi_->setFrame(frame()); + if (frame_) { + disconnect(frame_, SIGNAL(modified()), this, SLOT(onFrameModified())); + } + + frame_ = mcf; + interpolationKfi_->setFrame(frame()); + + connect(frame_, SIGNAL(modified()), this, SLOT(onFrameModified())); + onFrameModified(); } /*! Returns the distance from the Camera center to sceneCenter(), projected along the Camera Z axis. Used by zNear() and zFar() to optimize the Z range. */ -float Camera::distanceToSceneCenter() const +qreal Camera::distanceToSceneCenter() const { - return fabs((frame()->coordinatesOf(sceneCenter())).z); + return fabs((frame()->coordinatesOf(sceneCenter())).z); } @@ -292,18 +315,18 @@ float Camera::distanceToSceneCenter() const glOrtho( -halfWidth, halfWidth, -halfHeight, halfHeight, zNear(), zFar() ) \endcode - These values are proportional to the Camera (z projected) distance to the revolveAroundPoint(). + These values are proportional to the Camera (z projected) distance to the pivotPoint(). When zooming on the object, the Camera is translated forward \e and its frustum is narrowed, making the object appear bigger on screen, as intuitively expected. - Overload this method to change this behavior if desired, as is done in the + Overload this method to change this behavior if desired, as is done in the standardCamera example. */ void Camera::getOrthoWidthHeight(GLdouble& halfWidth, GLdouble& halfHeight) const { - const float dist = orthoCoef_ * fabs(cameraCoordinatesOf(revolveAroundPoint()).z); - //#CONNECTION# fitScreenRegion - halfWidth = dist * ((aspectRatio() < 1.0) ? 1.0 : aspectRatio()); - halfHeight = dist * ((aspectRatio() < 1.0) ? 1.0/aspectRatio() : 1.0); + const qreal dist = orthoCoef_ * fabs(cameraCoordinatesOf(pivotPoint()).z); + //#CONNECTION# fitScreenRegion + halfWidth = dist * ((aspectRatio() < 1.0) ? 1.0 : aspectRatio()); + halfHeight = dist * ((aspectRatio() < 1.0) ? 1.0/aspectRatio() : 1.0); } @@ -326,38 +349,42 @@ void Camera::getOrthoWidthHeight(GLdouble& halfWidth, GLdouble& halfHeight) cons does it otherwise. */ void Camera::computeProjectionMatrix() const { - const float ZNear = zNear(); - const float ZFar = zFar(); + if (projectionMatrixIsUpToDate_) return; - switch (type()) - { - case Camera::PERSPECTIVE: - { - // #CONNECTION# all non null coefficients were set to 0.0 in constructor. - const float f = 1.0/tan(fieldOfView()/2.0); - projectionMatrix_[0] = f/aspectRatio(); - projectionMatrix_[5] = f; - projectionMatrix_[10] = (ZNear + ZFar) / (ZNear - ZFar); - projectionMatrix_[11] = -1.0; - projectionMatrix_[14] = 2.0 * ZNear * ZFar / (ZNear - ZFar); - projectionMatrix_[15] = 0.0; - // same as gluPerspective( 180.0*fieldOfView()/M_PI, aspectRatio(), zNear(), zFar() ); - break; - } - case Camera::ORTHOGRAPHIC: - { - GLdouble w, h; - getOrthoWidthHeight(w,h); - projectionMatrix_[0] = 1.0/w; - projectionMatrix_[5] = 1.0/h; - projectionMatrix_[10] = -2.0/(ZFar - ZNear); - projectionMatrix_[11] = 0.0; - projectionMatrix_[14] = -(ZFar + ZNear)/(ZFar - ZNear); - projectionMatrix_[15] = 1.0; - // same as glOrtho( -w, w, -h, h, zNear(), zFar() ); - break; - } - } + const qreal ZNear = zNear(); + const qreal ZFar = zFar(); + + switch (type()) + { + case Camera::PERSPECTIVE: + { + // #CONNECTION# all non null coefficients were set to 0.0 in constructor. + const qreal f = 1.0/tan(fieldOfView()/2.0); + projectionMatrix_[0] = f/aspectRatio(); + projectionMatrix_[5] = f; + projectionMatrix_[10] = (ZNear + ZFar) / (ZNear - ZFar); + projectionMatrix_[11] = -1.0; + projectionMatrix_[14] = 2.0 * ZNear * ZFar / (ZNear - ZFar); + projectionMatrix_[15] = 0.0; + // same as gluPerspective( 180.0*fieldOfView()/M_PI, aspectRatio(), zNear(), zFar() ); + break; + } + case Camera::ORTHOGRAPHIC: + { + GLdouble w, h; + getOrthoWidthHeight(w,h); + projectionMatrix_[0] = 1.0/w; + projectionMatrix_[5] = 1.0/h; + projectionMatrix_[10] = -2.0/(ZFar - ZNear); + projectionMatrix_[11] = 0.0; + projectionMatrix_[14] = -(ZFar + ZNear)/(ZFar - ZNear); + projectionMatrix_[15] = 1.0; + // same as glOrtho( -w, w, -h, h, zNear(), zFar() ); + break; + } + } + + projectionMatrixIsUpToDate_ = true; } /*! Computes the modelView matrix associated with the Camera's position() and orientation(). @@ -372,42 +399,46 @@ void Camera::computeProjectionMatrix() const does it otherwise. */ void Camera::computeModelViewMatrix() const { - const Quaternion q = frame()->orientation(); + if (modelViewMatrixIsUpToDate_) return; + + const Quaternion q = frame()->orientation(); + + const qreal q00 = 2.0 * q[0] * q[0]; + const qreal q11 = 2.0 * q[1] * q[1]; + const qreal q22 = 2.0 * q[2] * q[2]; - const double q00 = 2.0l * q[0] * q[0]; - const double q11 = 2.0l * q[1] * q[1]; - const double q22 = 2.0l * q[2] * q[2]; + const qreal q01 = 2.0 * q[0] * q[1]; + const qreal q02 = 2.0 * q[0] * q[2]; + const qreal q03 = 2.0 * q[0] * q[3]; - const double q01 = 2.0l * q[0] * q[1]; - const double q02 = 2.0l * q[0] * q[2]; - const double q03 = 2.0l * q[0] * q[3]; + const qreal q12 = 2.0 * q[1] * q[2]; + const qreal q13 = 2.0 * q[1] * q[3]; - const double q12 = 2.0l * q[1] * q[2]; - const double q13 = 2.0l * q[1] * q[3]; + const qreal q23 = 2.0 * q[2] * q[3]; - const double q23 = 2.0l * q[2] * q[3]; + modelViewMatrix_[0] = 1.0 - q11 - q22; + modelViewMatrix_[1] = q01 - q23; + modelViewMatrix_[2] = q02 + q13; + modelViewMatrix_[3] = 0.0; - modelViewMatrix_[0] = 1.0l - q11 - q22; - modelViewMatrix_[1] = q01 - q23; - modelViewMatrix_[2] = q02 + q13; - modelViewMatrix_[3] = 0.0l; + modelViewMatrix_[4] = q01 + q23; + modelViewMatrix_[5] = 1.0 - q22 - q00; + modelViewMatrix_[6] = q12 - q03; + modelViewMatrix_[7] = 0.0; - modelViewMatrix_[4] = q01 + q23; - modelViewMatrix_[5] = 1.0l - q22 - q00; - modelViewMatrix_[6] = q12 - q03; - modelViewMatrix_[7] = 0.0l; + modelViewMatrix_[8] = q02 - q13; + modelViewMatrix_[9] = q12 + q03; + modelViewMatrix_[10] = 1.0 - q11 - q00; + modelViewMatrix_[11] = 0.0; - modelViewMatrix_[8] = q02 - q13; - modelViewMatrix_[9] = q12 + q03; - modelViewMatrix_[10] = 1.0l - q11 - q00; - modelViewMatrix_[11] = 0.0l; + const Vec t = q.inverseRotate(frame()->position()); - const Vec t = q.inverseRotate(frame()->position()); + modelViewMatrix_[12] = -t.x; + modelViewMatrix_[13] = -t.y; + modelViewMatrix_[14] = -t.z; + modelViewMatrix_[15] = 1.0; - modelViewMatrix_[12] = -t.x; - modelViewMatrix_[13] = -t.y; - modelViewMatrix_[14] = -t.z; - modelViewMatrix_[15] = 1.0l; + modelViewMatrixIsUpToDate_ = true; } @@ -431,15 +462,15 @@ void Camera::computeModelViewMatrix() const QGLWidget::makeCurrent() before this method in order to activate the right OpenGL context. */ void Camera::loadProjectionMatrix(bool reset) const { - // WARNING: makeCurrent must be called by every calling method - glMatrixMode(GL_PROJECTION); + // WARNING: makeCurrent must be called by every calling method + glMatrixMode(GL_PROJECTION); - if (reset) - glLoadIdentity(); + if (reset) + glLoadIdentity(); - computeProjectionMatrix(); + computeProjectionMatrix(); - glMultMatrixd(projectionMatrix_); + glMultMatrixd(projectionMatrix_); } /*! Loads the OpenGL \c GL_MODELVIEW matrix with the modelView matrix corresponding to the Camera. @@ -468,13 +499,13 @@ void Camera::loadProjectionMatrix(bool reset) const QGLWidget::makeCurrent() before this method in order to activate the right OpenGL context. */ void Camera::loadModelViewMatrix(bool reset) const { - // WARNING: makeCurrent must be called by every calling method - glMatrixMode(GL_MODELVIEW); - computeModelViewMatrix(); - if (reset) - glLoadMatrixd(modelViewMatrix_); - else - glMultMatrixd(modelViewMatrix_); + // WARNING: makeCurrent must be called by every calling method + glMatrixMode(GL_MODELVIEW); + computeModelViewMatrix(); + if (reset) + glLoadMatrixd(modelViewMatrix_); + else + glMultMatrixd(modelViewMatrix_); } /*! Same as loadProjectionMatrix() but for a stereo setup. @@ -496,7 +527,7 @@ void Camera::loadModelViewMatrix(bool reset) const glMatrixMode(GL_PROJECTION); glPushMatrix(); loadProjectionMatrixStereo(left_or_right); - glGetFloatv(GL_PROJECTION_MATRIX, m); + glGetDoublev(GL_PROJECTION_MATRIX, m); glPopMatrix(); \endcode Note that getProjectionMatrix() always returns the mono-vision matrix. @@ -504,39 +535,39 @@ void Camera::loadModelViewMatrix(bool reset) const \attention glMatrixMode is set to \c GL_PROJECTION. */ void Camera::loadProjectionMatrixStereo(bool leftBuffer) const { - float left, right, bottom, top; - float screenHalfWidth, halfWidth, side, shift, delta; + qreal left, right, bottom, top; + qreal screenHalfWidth, halfWidth, side, shift, delta; - glMatrixMode(GL_PROJECTION); - glLoadIdentity(); + glMatrixMode(GL_PROJECTION); + glLoadIdentity(); - switch (type()) - { - case Camera::PERSPECTIVE: - // compute half width of screen, - // corresponding to zero parallax plane to deduce decay of cameras - screenHalfWidth = focusDistance() * tan(horizontalFieldOfView() / 2.0); - shift = screenHalfWidth * IODistance() / physicalScreenWidth(); - // should be * current y / y total - // to take into account that the window doesn't cover the entire screen - - // compute half width of "view" at znear and the delta corresponding to - // the shifted camera to deduce what to set for asymmetric frustums - halfWidth = zNear() * tan(horizontalFieldOfView() / 2.0); - delta = shift * zNear() / focusDistance(); - side = leftBuffer ? -1.0 : 1.0; - - left = -halfWidth + side * delta; - right = halfWidth + side * delta; - top = halfWidth / aspectRatio(); - bottom = -top; - glFrustum(left, right, bottom, top, zNear(), zFar() ); - break; - - case Camera::ORTHOGRAPHIC: - qWarning("Camera::setProjectionMatrixStereo: Stereo not available with Ortho mode"); - break; - } + switch (type()) + { + case Camera::PERSPECTIVE: + // compute half width of screen, + // corresponding to zero parallax plane to deduce decay of cameras + screenHalfWidth = focusDistance() * tan(horizontalFieldOfView() / 2.0); + shift = screenHalfWidth * IODistance() / physicalScreenWidth(); + // should be * current y / y total + // to take into account that the window doesn't cover the entire screen + + // compute half width of "view" at znear and the delta corresponding to + // the shifted camera to deduce what to set for asymmetric frustums + halfWidth = zNear() * tan(horizontalFieldOfView() / 2.0); + delta = shift * zNear() / focusDistance(); + side = leftBuffer ? -1.0 : 1.0; + + left = -halfWidth + side * delta; + right = halfWidth + side * delta; + top = halfWidth / aspectRatio(); + bottom = -top; + glFrustum(left, right, bottom, top, zNear(), zFar() ); + break; + + case Camera::ORTHOGRAPHIC: + qWarning("Camera::setProjectionMatrixStereo: Stereo not available with Ortho mode"); + break; + } } /*! Same as loadModelViewMatrix() but for a stereo setup. @@ -559,51 +590,59 @@ void Camera::loadProjectionMatrixStereo(bool leftBuffer) const \attention glMatrixMode is set to \c GL_MODELVIEW. */ void Camera::loadModelViewMatrixStereo(bool leftBuffer) const { - // WARNING: makeCurrent must be called by every calling method - glMatrixMode(GL_MODELVIEW); + // WARNING: makeCurrent must be called by every calling method + glMatrixMode(GL_MODELVIEW); - float halfWidth = focusDistance() * tan(horizontalFieldOfView() / 2.0); - float shift = halfWidth * IODistance() / physicalScreenWidth(); // * current window width / full screen width + qreal halfWidth = focusDistance() * tan(horizontalFieldOfView() / 2.0); + qreal shift = halfWidth * IODistance() / physicalScreenWidth(); // * current window width / full screen width - computeModelViewMatrix(); - if (leftBuffer) - modelViewMatrix_[12] -= shift; - else - modelViewMatrix_[12] += shift; - glLoadMatrixd(modelViewMatrix_); + computeModelViewMatrix(); + if (leftBuffer) + modelViewMatrix_[12] -= shift; + else + modelViewMatrix_[12] += shift; + glLoadMatrixd(modelViewMatrix_); } /*! Fills \p m with the Camera projection matrix values. - Calls computeProjectionMatrix() to define the Camera projection matrix. + Based on computeProjectionMatrix() to make sure the Camera projection matrix is up to date. This matrix only reflects the Camera's internal parameters and it may differ from the \c GL_PROJECTION matrix retrieved using \c glGetDoublev(GL_PROJECTION_MATRIX, m). It actually represents the state of the \c GL_PROJECTION after QGLViewer::preDraw(), at the beginning of QGLViewer::draw(). If you modified the \c GL_PROJECTION matrix (for instance using QGLViewer::startScreenCoordinatesSystem()), the two results differ. - + The result is an OpenGL 4x4 matrix, which is given in \e column-major order (see \c glMultMatrix man page for details). See also getModelViewMatrix() and setFromProjectionMatrix(). */ void Camera::getProjectionMatrix(GLdouble m[16]) const { - // May not be needed, but easier and more robust like this. - computeProjectionMatrix(); - for (unsigned short i=0; i<16; ++i) - m[i] = projectionMatrix_[i]; + computeProjectionMatrix(); + for (unsigned short i=0; i<16; ++i) + m[i] = projectionMatrix_[i]; +} + +/*! Overloaded getProjectionMatrix(GLdouble m[16]) method using a \c GLfloat array instead. */ +void Camera::getProjectionMatrix(GLfloat m[16]) const +{ + static GLdouble mat[16]; + getProjectionMatrix(mat); + for (unsigned short i=0; i<16; ++i) + m[i] = float(mat[i]); } /*! Fills \p m with the Camera modelView matrix values. First calls computeModelViewMatrix() to define the Camera modelView matrix. - Note that this matrix is usually \e not the one you would get from a \c + Note that this matrix may \e not be the one you would get from a \c glGetDoublev(GL_MODELVIEW_MATRIX, m). It actually represents the state of the \c - GL_MODELVIEW after QGLViewer::preDraw(), at the beginning of QGLViewer::draw(). It converts from + GL_MODELVIEW after QGLViewer::preDraw(), at the \e beginning of QGLViewer::draw(). It converts from the world to the Camera coordinate system. As soon as you modify the \c GL_MODELVIEW in your - QGLViewer::draw() method, the two matrices differ. + QGLViewer::draw() method (using glTranslate, glRotate... or similar methods), the two matrices differ. The result is an OpenGL 4x4 matrix, which is given in \e column-major order (see \c glMultMatrix man page for details). @@ -611,11 +650,21 @@ void Camera::getProjectionMatrix(GLdouble m[16]) const See also getProjectionMatrix() and setFromModelViewMatrix(). */ void Camera::getModelViewMatrix(GLdouble m[16]) const { - // May not be needed, but easier like this. - // Prevents from retrieving matrix in stereo mode -> overwrites shifted value. - computeModelViewMatrix(); - for (unsigned short i=0; i<16; ++i) - m[i] = modelViewMatrix_[i]; + // May not be needed, but easier like this. + // Prevents from retrieving matrix in stereo mode -> overwrites shifted value. + computeModelViewMatrix(); + for (unsigned short i=0; i<16; ++i) + m[i] = modelViewMatrix_[i]; +} + + +/*! Overloaded getModelViewMatrix(GLdouble m[16]) method using a \c GLfloat array instead. */ +void Camera::getModelViewMatrix(GLfloat m[16]) const +{ + static GLdouble mat[16]; + getModelViewMatrix(mat); + for (unsigned short i=0; i<16; ++i) + m[i] = float(mat[i]); } /*! Fills \p m with the product of the ModelView and Projection matrices. @@ -623,125 +672,134 @@ void Camera::getModelViewMatrix(GLdouble m[16]) const Calls getModelViewMatrix() and getProjectionMatrix() and then fills \p m with the product of these two matrices. */ void Camera::getModelViewProjectionMatrix(GLdouble m[16]) const { - GLdouble mv[16]; - GLdouble proj[16]; - getModelViewMatrix(mv); - getProjectionMatrix(proj); - - for (unsigned short i=0; i<4; ++i) - { - for (unsigned short j=0; j<4; ++j) - { - double sum = 0.0; - for (unsigned short k=0; k<4; ++k) - sum += proj[i+4*k]*mv[k+4*j]; - m[i+4*j] = sum; - } - } -} + GLdouble mv[16]; + GLdouble proj[16]; + getModelViewMatrix(mv); + getProjectionMatrix(proj); -#ifndef DOXYGEN -void Camera::getProjectionMatrix(GLfloat m[16]) const -{ - qWarning("Warning : Camera::getProjectionMatrix requires a GLdouble matrix array"); - static GLdouble mat[16]; - getProjectionMatrix(mat); - for (int i=0; i<16; ++i) - m[i] = float(mat[i]); + for (unsigned short i=0; i<4; ++i) + { + for (unsigned short j=0; j<4; ++j) + { + qreal sum = 0.0; + for (unsigned short k=0; k<4; ++k) + sum += proj[i+4*k]*mv[k+4*j]; + m[i+4*j] = sum; + } + } } -void Camera::getModelViewMatrix(GLfloat m[16]) const +/*! Overloaded getModelViewProjectionMatrix(GLdouble m[16]) method using a \c GLfloat array instead. */ +void Camera::getModelViewProjectionMatrix(GLfloat m[16]) const { - qWarning("Warning : Camera::getModelViewMatrix requires a GLdouble matrix array"); - static GLdouble mat[16]; - getModelViewMatrix(mat); - for (int i=0; i<16; ++i) - m[i] = float(mat[i]); + static GLdouble mat[16]; + getModelViewProjectionMatrix(mat); + for (unsigned short i=0; i<16; ++i) + m[i] = float(mat[i]); } -#endif /*! Sets the sceneRadius() value. Negative values are ignored. \attention This methods also sets focusDistance() to sceneRadius() / tan(fieldOfView()/2) and flySpeed() to 1% of sceneRadius(). */ -void Camera::setSceneRadius(float radius) +void Camera::setSceneRadius(qreal radius) { - if (radius <= 0.0) - { - qWarning("Scene radius must be positive - Ignoring value"); - return; - } + if (radius <= 0.0) + { + qWarning("Scene radius must be positive - Ignoring value"); + return; + } - sceneRadius_ = radius; + sceneRadius_ = radius; + projectionMatrixIsUpToDate_ = false; - setFocusDistance(sceneRadius() / tan(fieldOfView()/2.0)); + setFocusDistance(sceneRadius() / tan(fieldOfView()/2.0)); - frame()->setFlySpeed(0.01*sceneRadius()); + frame()->setFlySpeed(0.01*sceneRadius()); } /*! Similar to setSceneRadius() and setSceneCenter(), but the scene limits are defined by a (world axis aligned) bounding box. */ void Camera::setSceneBoundingBox(const Vec& min, const Vec& max) { - setSceneCenter((min+max)/2.0); - setSceneRadius(0.5*(max-min).norm()); + setSceneCenter((min+max)/2.0); + setSceneRadius(0.5*(max-min).norm()); } /*! Sets the sceneCenter(). - \attention This method also sets the revolveAroundPoint() to sceneCenter(). */ + \attention This method also sets the pivotPoint() to sceneCenter(). */ void Camera::setSceneCenter(const Vec& center) { - sceneCenter_ = center; - setRevolveAroundPoint(sceneCenter()); + sceneCenter_ = center; + setPivotPoint(sceneCenter()); + projectionMatrixIsUpToDate_ = false; } /*! setSceneCenter() to the result of pointUnderPixel(\p pixel). Returns \c true if a pointUnderPixel() was found and sceneCenter() was actually changed. - See also setRevolveAroundPointFromPixel(). See the pointUnderPixel() documentation. */ + See also setPivotPointFromPixel(). See the pointUnderPixel() documentation. */ bool Camera::setSceneCenterFromPixel(const QPoint& pixel) { - bool found; - Vec point = pointUnderPixel(pixel, found); - if (found) - setSceneCenter(point); - return found; + bool found; + Vec point = pointUnderPixel(pixel, found); + if (found) + setSceneCenter(point); + return found; } -/*! Changes the revolveAroundPoint() to \p rap (defined in the world coordinate system). */ -void Camera::setRevolveAroundPoint(const Vec& rap) +#ifndef DOXYGEN +void Camera::setRevolveAroundPoint(const Vec& point) { + qWarning("setRevolveAroundPoint() is deprecated, use setPivotPoint() instead"); + setPivotPoint(point); +} +bool Camera::setRevolveAroundPointFromPixel(const QPoint& pixel) { + qWarning("setRevolveAroundPointFromPixel() is deprecated, use setPivotPointFromPixel() instead"); + return setPivotPointFromPixel(pixel); +} +Vec Camera::revolveAroundPoint() const { + qWarning("revolveAroundPoint() is deprecated, use pivotPoint() instead"); + return pivotPoint(); +} +#endif + +/*! Changes the pivotPoint() to \p point (defined in the world coordinate system). */ +void Camera::setPivotPoint(const Vec& point) { - const float prevDist = fabs(cameraCoordinatesOf(revolveAroundPoint()).z); + const qreal prevDist = fabs(cameraCoordinatesOf(pivotPoint()).z); - frame()->setRevolveAroundPoint(rap); + // If frame's RAP is set directly, projectionMatrixIsUpToDate_ should also be + // set to false to ensure proper recomputation of the ORTHO projection matrix. + frame()->setPivotPoint(point); - // orthoCoef_ is used to compensate for changes of the revolveAroundPoint, so that the image does - // not change when the revolveAroundPoint is changed in ORTHOGRAPHIC mode. - const float newDist = fabs(cameraCoordinatesOf(revolveAroundPoint()).z); - // Prevents division by zero when rap is set to camera position - if ((prevDist > 1E-9) && (newDist > 1E-9)) - orthoCoef_ *= prevDist / newDist; + // orthoCoef_ is used to compensate for changes of the pivotPoint, so that the image does + // not change when the pivotPoint is changed in ORTHOGRAPHIC mode. + const qreal newDist = fabs(cameraCoordinatesOf(pivotPoint()).z); + // Prevents division by zero when rap is set to camera position + if ((prevDist > 1E-9) && (newDist > 1E-9)) + orthoCoef_ *= prevDist / newDist; + projectionMatrixIsUpToDate_ = false; } -/*! The revolveAroundPoint() is set to the point located under \p pixel on screen. +/*! The pivotPoint() is set to the point located under \p pixel on screen. Returns \c true if a pointUnderPixel() was found. If no point was found under \p pixel, the -revolveAroundPoint() is left unchanged. +pivotPoint() is left unchanged. \p pixel is expressed in Qt format (origin in the upper left corner of the window). See pointUnderPixel(). See also setSceneCenterFromPixel(). */ -bool Camera::setRevolveAroundPointFromPixel(const QPoint& pixel) +bool Camera::setPivotPointFromPixel(const QPoint& pixel) { - bool found; - Vec point = pointUnderPixel(pixel, found); - if (found) - setRevolveAroundPoint(point); - return found; + bool found; + Vec point = pointUnderPixel(pixel, found); + if (found) + setPivotPoint(point); + return found; } /*! Returns the ratio between pixel and OpenGL units at \p position. @@ -758,21 +816,21 @@ bool Camera::setRevolveAroundPointFromPixel(const QPoint& pixel) glVertex3fv(sceneCenter() + 20 * pixelGLRatio(sceneCenter()) * camera()->upVector()); glEnd(); \endcode */ -float Camera::pixelGLRatio(const Vec& position) const +qreal Camera::pixelGLRatio(const Vec& position) const { - switch (type()) - { - case Camera::PERSPECTIVE : - return 2.0 * fabs((frame()->coordinatesOf(position)).z) * tan(fieldOfView()/2.0) / screenHeight(); - case Camera::ORTHOGRAPHIC : - { - GLdouble w, h; - getOrthoWidthHeight(w,h); - return 2.0 * h / screenHeight(); - } - } - // Bad compilers complain - return 1.0; + switch (type()) + { + case Camera::PERSPECTIVE : + return 2.0 * fabs((frame()->coordinatesOf(position)).z) * tan(fieldOfView()/2.0) / screenHeight(); + case Camera::ORTHOGRAPHIC : + { + GLdouble w, h; + getOrthoWidthHeight(w,h); + return 2.0 * h / screenHeight(); + } + } + // Bad compilers complain + return 1.0; } /*! Changes the Camera fieldOfView() so that the entire scene (defined by QGLViewer::sceneCenter() @@ -802,10 +860,10 @@ float Camera::pixelGLRatio(const Vec& position) const resolution, although it may miss some parts of the scene. */ void Camera::setFOVToFitScene() { - if (distanceToSceneCenter() > sqrt(2.0)*sceneRadius()) - setFieldOfView(2.0 * asin(sceneRadius() / distanceToSceneCenter())); - else - setFieldOfView(M_PI / 2.0f); + if (distanceToSceneCenter() > sqrt(2.0)*sceneRadius()) + setFieldOfView(2.0 * asin(sceneRadius() / distanceToSceneCenter())); + else + setFieldOfView(M_PI / 2.0); } /*! Makes the Camera smoothly zoom on the pointUnderPixel() \p pixel. @@ -816,34 +874,34 @@ void Camera::setFOVToFitScene() See also interpolateToFitScene(). */ void Camera::interpolateToZoomOnPixel(const QPoint& pixel) { - const float coef = 0.1f; + const qreal coef = 0.1; - bool found; - Vec target = pointUnderPixel(pixel, found); + bool found; + Vec target = pointUnderPixel(pixel, found); - if (!found) - return; + if (!found) + return; - if (interpolationKfi_->interpolationIsStarted()) - interpolationKfi_->stopInterpolation(); + if (interpolationKfi_->interpolationIsStarted()) + interpolationKfi_->stopInterpolation(); - interpolationKfi_->deletePath(); - interpolationKfi_->addKeyFrame(*(frame())); + interpolationKfi_->deletePath(); + interpolationKfi_->addKeyFrame(*(frame())); - interpolationKfi_->addKeyFrame(Frame(0.3f*frame()->position() + 0.7f*target, frame()->orientation()), 0.4f); + interpolationKfi_->addKeyFrame(Frame(0.3*frame()->position() + 0.7*target, frame()->orientation()), 0.4); - // Small hack: attach a temporary frame to take advantage of lookAt without modifying frame - static ManipulatedCameraFrame* tempFrame = new ManipulatedCameraFrame(); - ManipulatedCameraFrame* const originalFrame = frame(); - tempFrame->setPosition(coef*frame()->position() + (1.0-coef)*target); - tempFrame->setOrientation(frame()->orientation()); - setFrame(tempFrame); - lookAt(target); - setFrame(originalFrame); + // Small hack: attach a temporary frame to take advantage of lookAt without modifying frame + static ManipulatedCameraFrame* tempFrame = new ManipulatedCameraFrame(); + ManipulatedCameraFrame* const originalFrame = frame(); + tempFrame->setPosition(coef*frame()->position() + (1.0-coef)*target); + tempFrame->setOrientation(frame()->orientation()); + setFrame(tempFrame); + lookAt(target); + setFrame(originalFrame); - interpolationKfi_->addKeyFrame(*(tempFrame), 1.0); + interpolationKfi_->addKeyFrame(*(tempFrame), 1.0); - interpolationKfi_->startInterpolation(); + interpolationKfi_->startInterpolation(); } /*! Interpolates the Camera on a one second KeyFrameInterpolator path so that the entire scene fits @@ -854,43 +912,43 @@ void Camera::interpolateToZoomOnPixel(const QPoint& pixel) The orientation() of the Camera is not modified. See also interpolateToZoomOnPixel(). */ void Camera::interpolateToFitScene() { - if (interpolationKfi_->interpolationIsStarted()) - interpolationKfi_->stopInterpolation(); + if (interpolationKfi_->interpolationIsStarted()) + interpolationKfi_->stopInterpolation(); - interpolationKfi_->deletePath(); - interpolationKfi_->addKeyFrame(*(frame())); + interpolationKfi_->deletePath(); + interpolationKfi_->addKeyFrame(*(frame())); - // Small hack: attach a temporary frame to take advantage of lookAt without modifying frame - static ManipulatedCameraFrame* tempFrame = new ManipulatedCameraFrame(); - ManipulatedCameraFrame* const originalFrame = frame(); - tempFrame->setPosition(frame()->position()); - tempFrame->setOrientation(frame()->orientation()); - setFrame(tempFrame); - showEntireScene(); - setFrame(originalFrame); + // Small hack: attach a temporary frame to take advantage of lookAt without modifying frame + static ManipulatedCameraFrame* tempFrame = new ManipulatedCameraFrame(); + ManipulatedCameraFrame* const originalFrame = frame(); + tempFrame->setPosition(frame()->position()); + tempFrame->setOrientation(frame()->orientation()); + setFrame(tempFrame); + showEntireScene(); + setFrame(originalFrame); - interpolationKfi_->addKeyFrame(*(tempFrame)); + interpolationKfi_->addKeyFrame(*(tempFrame)); - interpolationKfi_->startInterpolation(); + interpolationKfi_->startInterpolation(); } /*! Smoothly interpolates the Camera on a KeyFrameInterpolator path so that it goes to \p fr. - + \p fr is expressed in world coordinates. \p duration tunes the interpolation speed (default is 1 second). - + See also interpolateToFitScene() and interpolateToZoomOnPixel(). */ -void Camera::interpolateTo(const Frame& fr, float duration) +void Camera::interpolateTo(const Frame& fr, qreal duration) { - if (interpolationKfi_->interpolationIsStarted()) - interpolationKfi_->stopInterpolation(); + if (interpolationKfi_->interpolationIsStarted()) + interpolationKfi_->stopInterpolation(); - interpolationKfi_->deletePath(); - interpolationKfi_->addKeyFrame(*(frame())); - interpolationKfi_->addKeyFrame(fr, duration); + interpolationKfi_->deletePath(); + interpolationKfi_->addKeyFrame(*(frame())); + interpolationKfi_->addKeyFrame(fr, duration); - interpolationKfi_->startInterpolation(); + interpolationKfi_->startInterpolation(); } @@ -912,13 +970,13 @@ void Camera::interpolateTo(const Frame& fr, float duration) to your scene. Loose boundaries will result in imprecision along the viewing direction. */ Vec Camera::pointUnderPixel(const QPoint& pixel, bool& found) const { - float depth; - // Qt uses upper corner for its origin while GL uses the lower corner. - glReadPixels(pixel.x(), screenHeight()-1-pixel.y(), 1, 1, GL_DEPTH_COMPONENT, GL_FLOAT, &depth); - found = depth < 1.0; - Vec point(pixel.x(), pixel.y(), depth); - point = unprojectedCoordinatesOf(point); - return point; + float depth; + // Qt uses upper corner for its origin while GL uses the lower corner. + glReadPixels(pixel.x(), screenHeight()-1-pixel.y(), 1, 1, GL_DEPTH_COMPONENT, GL_FLOAT, &depth); + found = depth < 1.0; + Vec point(pixel.x(), pixel.y(), depth); + point = unprojectedCoordinatesOf(point); + return point; } /*! Moves the Camera so that the entire scene is visible. @@ -928,7 +986,7 @@ Vec Camera::pointUnderPixel(const QPoint& pixel, bool& found) const You will typically use this method in QGLViewer::init() after you defined a new sceneRadius(). */ void Camera::showEntireScene() { - fitSphere(sceneCenter(), sceneRadius()); + fitSphere(sceneCenter(), sceneRadius()); } /*! Moves the Camera so that its sceneCenter() is projected on the center of the window. The @@ -938,7 +996,7 @@ void Camera::showEntireScene() showEntireScene().*/ void Camera::centerScene() { - frame()->projectOnLine(sceneCenter(), viewDirection()); + frame()->projectOnLine(sceneCenter(), viewDirection()); } /*! Sets the Camera orientation(), so that it looks at point \p target (defined in the world @@ -949,45 +1007,45 @@ void Camera::centerScene() See also setUpVector(), setOrientation(), showEntireScene(), fitSphere() and fitBoundingBox(). */ void Camera::lookAt(const Vec& target) { - setViewDirection(target - position()); + setViewDirection(target - position()); } -/*! Moves the Camera so that the sphere defined by (\p center, \p radius) is visible and fits the window. +/*! Moves the Camera so that the sphere defined by (\p center, \p radius) is visible and fits in the frustum. - The Camera is simply translated along its viewDirection() so that the sphere fits the screen. Its + The Camera is simply translated to center the sphere in the screen and make it fit the frustum. Its orientation() and its fieldOfView() are unchanged. You should therefore orientate the Camera before you call this method. See lookAt(), setOrientation() and setUpVector(). */ -void Camera::fitSphere(const Vec& center, float radius) +void Camera::fitSphere(const Vec& center, qreal radius) { - float distance = 0.0f; - switch (type()) - { - case Camera::PERSPECTIVE : - { - const float yview = radius / sin(fieldOfView()/2.0); - const float xview = radius / sin(horizontalFieldOfView()/2.0); - distance = qMax(xview,yview); - break; - } - case Camera::ORTHOGRAPHIC : - { - distance = ((center-revolveAroundPoint()) * viewDirection()) + (radius / orthoCoef_); - break; - } - } - Vec newPos(center - distance * viewDirection()); - frame()->setPositionWithConstraint(newPos); + qreal distance = 0.0; + switch (type()) + { + case Camera::PERSPECTIVE : + { + const qreal yview = radius / sin(fieldOfView() / 2.0); + const qreal xview = radius / sin(horizontalFieldOfView() / 2.0); + distance = qMax(xview, yview); + break; + } + case Camera::ORTHOGRAPHIC : + { + distance = ((center-pivotPoint()) * viewDirection()) + (radius / orthoCoef_); + break; + } + } + Vec newPos(center - distance * viewDirection()); + frame()->setPositionWithConstraint(newPos); } /*! Moves the Camera so that the (world axis aligned) bounding box (\p min, \p max) is entirely visible, using fitSphere(). */ void Camera::fitBoundingBox(const Vec& min, const Vec& max) { - float diameter = qMax(fabs(max[1]-min[1]), fabs(max[0]-min[0])); - diameter = qMax(fabsf(max[2]-min[2]), diameter); - fitSphere(0.5*(min+max), 0.5*diameter); + qreal diameter = qMax(fabs(max[1]-min[1]), fabs(max[0]-min[0])); + diameter = qMax(fabs(max[2]-min[2]), diameter); + fitSphere(0.5*(min+max), 0.5*diameter); } /*! Moves the Camera so that the rectangular screen region defined by \p rectangle (pixel units, @@ -999,43 +1057,43 @@ void Camera::fitBoundingBox(const Vec& min, const Vec& max) that is used to define the 3D rectangle that is eventually fitted. */ void Camera::fitScreenRegion(const QRect& rectangle) { - const Vec vd = viewDirection(); - const float distToPlane = distanceToSceneCenter(); - const QPoint center = rectangle.center(); + const Vec vd = viewDirection(); + const qreal distToPlane = distanceToSceneCenter(); + const QPoint center = rectangle.center(); - Vec orig, dir; - convertClickToLine( center, orig, dir ); - Vec newCenter = orig + distToPlane / (dir*vd) * dir; + Vec orig, dir; + convertClickToLine( center, orig, dir ); + Vec newCenter = orig + distToPlane / (dir*vd) * dir; - convertClickToLine( QPoint(rectangle.x(), center.y()), orig, dir ); - const Vec pointX = orig + distToPlane / (dir*vd) * dir; + convertClickToLine( QPoint(rectangle.x(), center.y()), orig, dir ); + const Vec pointX = orig + distToPlane / (dir*vd) * dir; - convertClickToLine( QPoint(center.x(), rectangle.y()), orig, dir ); - const Vec pointY = orig + distToPlane / (dir*vd) * dir; + convertClickToLine( QPoint(center.x(), rectangle.y()), orig, dir ); + const Vec pointY = orig + distToPlane / (dir*vd) * dir; - float distance = 0.0f; - switch (type()) - { - case Camera::PERSPECTIVE : - { - const float distX = (pointX-newCenter).norm() / sin(horizontalFieldOfView()/2.0); - const float distY = (pointY-newCenter).norm() / sin(fieldOfView()/2.0); - distance = qMax(distX, distY); - break; - } - case Camera::ORTHOGRAPHIC : - { - const float dist = ((newCenter-revolveAroundPoint()) * vd); - //#CONNECTION# getOrthoWidthHeight - const float distX = (pointX-newCenter).norm() / orthoCoef_ / ((aspectRatio() < 1.0) ? 1.0 : aspectRatio()); - const float distY = (pointY-newCenter).norm() / orthoCoef_ / ((aspectRatio() < 1.0) ? 1.0/aspectRatio() : 1.0); - distance = dist + qMax(distX, distY); - break; - } - } + qreal distance = 0.0; + switch (type()) + { + case Camera::PERSPECTIVE : + { + const qreal distX = (pointX-newCenter).norm() / sin(horizontalFieldOfView()/2.0); + const qreal distY = (pointY-newCenter).norm() / sin(fieldOfView()/2.0); + distance = qMax(distX, distY); + break; + } + case Camera::ORTHOGRAPHIC : + { + const qreal dist = ((newCenter-pivotPoint()) * vd); + //#CONNECTION# getOrthoWidthHeight + const qreal distX = (pointX-newCenter).norm() / orthoCoef_ / ((aspectRatio() < 1.0) ? 1.0 : aspectRatio()); + const qreal distY = (pointY-newCenter).norm() / orthoCoef_ / ((aspectRatio() < 1.0) ? 1.0/aspectRatio() : 1.0); + distance = dist + qMax(distX, distY); + break; + } + } - Vec newPos(newCenter - distance * vd); - frame()->setPositionWithConstraint(newPos); + Vec newPos(newCenter - distance * vd); + frame()->setPositionWithConstraint(newPos); } /*! Rotates the Camera so that its upVector() becomes \p up (defined in the world coordinate @@ -1045,25 +1103,27 @@ void Camera::fitScreenRegion(const QRect& rectangle) Use this method in order to define the Camera horizontal plane. When \p noMove is set to \c false, the orientation modification is compensated by a translation, so - that the revolveAroundPoint() stays projected at the same position on screen. This is especially - useful when the Camera is an observer of the scene (default mouse binding). + that the pivotPoint() stays projected at the same position on screen. This is especially + useful when the Camera is used as an observer of the scene (default mouse binding). When \p noMove is \c true (default), the Camera position() is left unchanged, which is an intuitive behavior when the Camera is in a walkthrough fly mode (see the QGLViewer::MOVE_FORWARD and - QGLViewer::MOVE_BACKWARD QGLViewer::MouseAction). + QGLViewer::MOVE_BACKWARD QGLViewer::MouseAction). + + The frame()'s ManipulatedCameraFrame::sceneUpVector() is set accordingly. See also setViewDirection(), lookAt() and setOrientation(). */ void Camera::setUpVector(const Vec& up, bool noMove) { - Quaternion q(Vec(0.0, 1.0, 0.0), frame()->transformOf(up)); + Quaternion q(Vec(0.0, 1.0, 0.0), frame()->transformOf(up)); - if (!noMove) - frame()->setPosition(revolveAroundPoint() - (frame()->orientation()*q).rotate(frame()->coordinatesOf(revolveAroundPoint()))); + if (!noMove) + frame()->setPosition(pivotPoint() - (frame()->orientation()*q).rotate(frame()->coordinatesOf(pivotPoint()))); - frame()->rotate(q); + frame()->rotate(q); - // Useful in fly mode to keep the horizontal direction. - frame()->updateFlyUpVector(); + // Useful in fly mode to keep the horizontal direction. + frame()->updateSceneUpVector(); } /*! Sets the orientation() of the Camera using polar coordinates. @@ -1077,20 +1137,20 @@ void Camera::setUpVector(const Vec& up, bool noMove) This method can be useful to create Quicktime VR panoramic sequences, see the QGLViewer::saveSnapshot() documentation for details. */ -void Camera::setOrientation(float theta, float phi) +void Camera::setOrientation(qreal theta, qreal phi) { - Vec axis(0.0, 1.0, 0.0); - const Quaternion rot1(axis, theta); - axis = Vec(-cos(theta), 0., sin(theta)); - const Quaternion rot2(axis, phi); - setOrientation(rot1 * rot2); + Vec axis(0.0, 1.0, 0.0); + const Quaternion rot1(axis, theta); + axis = Vec(-cos(theta), 0.0, sin(theta)); + const Quaternion rot2(axis, phi); + setOrientation(rot1 * rot2); } /*! Sets the Camera orientation(), defined in the world coordinate system. */ void Camera::setOrientation(const Quaternion& q) { - frame()->setOrientation(q); - frame()->updateFlyUpVector(); + frame()->setOrientation(q); + frame()->updateSceneUpVector(); } /*! Rotates the Camera so that its viewDirection() is \p direction (defined in the world coordinate @@ -1100,36 +1160,119 @@ void Camera::setOrientation(const Quaternion& q) upVector()) is preserved. See also lookAt() and setUpVector(). */ void Camera::setViewDirection(const Vec& direction) { - if (direction.squaredNorm() < 1E-10) - return; + if (direction.squaredNorm() < 1E-10) + return; - Vec xAxis = direction ^ upVector(); - if (xAxis.squaredNorm() < 1E-10) - { - // target is aligned with upVector, this means a rotation around X axis - // X axis is then unchanged, let's keep it ! - xAxis = frame()->inverseTransformOf(Vec(1.0, 0.0, 0.0)); - } + Vec xAxis = direction ^ upVector(); + if (xAxis.squaredNorm() < 1E-10) + { + // target is aligned with upVector, this means a rotation around X axis + // X axis is then unchanged, let's keep it ! + xAxis = frame()->inverseTransformOf(Vec(1.0, 0.0, 0.0)); + } - Quaternion q; - q.setFromRotatedBasis(xAxis, xAxis^direction, -direction); - frame()->setOrientationWithConstraint(q); + Quaternion q; + q.setFromRotatedBasis(xAxis, xAxis^direction, -direction); + frame()->setOrientationWithConstraint(q); } // Compute a 3 by 3 determinant. -static float det(float m00,float m01,float m02, - float m10,float m11,float m12, - float m20,float m21,float m22) +static qreal det(qreal m00,qreal m01,qreal m02, + qreal m10,qreal m11,qreal m12, + qreal m20,qreal m21,qreal m22) { - return m00*m11*m22 + m01*m12*m20 + m02*m10*m21 - m20*m11*m02 - m10*m01*m22 - m00*m21*m12; + return m00*m11*m22 + m01*m12*m20 + m02*m10*m21 - m20*m11*m02 - m10*m01*m22 - m00*m21*m12; } -// Computes the index of element [i][j] in a \c float matrix[3][4]. +// Computes the index of element [i][j] in a \c qreal matrix[3][4]. static inline unsigned int ind(unsigned int i, unsigned int j) { - return (i*4+j); + return (i*4+j); +} + +/*! Returns the Camera position (the eye), defined in the world coordinate system. + +Use setPosition() to set the Camera position. Other convenient methods are showEntireScene() or +fitSphere(). Actually returns \c frame()->position(). + +This position corresponds to the projection center of a Camera::PERSPECTIVE Camera. It is not +located in the image plane, which is at a zNear() distance ahead. */ +Vec Camera::position() const { return frame()->position(); } + +/*! Returns the normalized up vector of the Camera, defined in the world coordinate system. + +Set using setUpVector() or setOrientation(). It is orthogonal to viewDirection() and to +rightVector(). + +It corresponds to the Y axis of the associated frame() (actually returns +frame()->inverseTransformOf(Vec(0.0, 1.0, 0.0)) ). */ +Vec Camera::upVector() const +{ + return frame()->inverseTransformOf(Vec(0.0, 1.0, 0.0)); +} +/*! Returns the normalized view direction of the Camera, defined in the world coordinate system. + +Change this value using setViewDirection(), lookAt() or setOrientation(). It is orthogonal to +upVector() and to rightVector(). + +This corresponds to the negative Z axis of the frame() ( frame()->inverseTransformOf(Vec(0.0, +0.0, -1.0)) ). */ +Vec Camera::viewDirection() const { return frame()->inverseTransformOf(Vec(0.0, 0.0, -1.0)); } + +/*! Returns the normalized right vector of the Camera, defined in the world coordinate system. + +This vector lies in the Camera horizontal plane, directed along the X axis (orthogonal to +upVector() and to viewDirection()). Set using setUpVector(), lookAt() or setOrientation(). + +Simply returns frame()->inverseTransformOf(Vec(1.0, 0.0, 0.0)). */ +Vec Camera::rightVector() const +{ + return frame()->inverseTransformOf(Vec(1.0, 0.0, 0.0)); } +/*! Returns the Camera orientation, defined in the world coordinate system. + +Actually returns \c frame()->orientation(). Use setOrientation(), setUpVector() or lookAt() to +set the Camera orientation. */ +Quaternion Camera::orientation() const { return frame()->orientation(); } + +/*! Sets the Camera position() (the eye), defined in the world coordinate system. */ +void Camera::setPosition(const Vec& pos) { frame()->setPosition(pos); } + +/*! Returns the Camera frame coordinates of a point \p src defined in world coordinates. + +worldCoordinatesOf() performs the inverse transformation. + +Note that the point coordinates are simply converted in a different coordinate system. They are +not projected on screen. Use projectedCoordinatesOf() for that. */ +Vec Camera::cameraCoordinatesOf(const Vec& src) const { return frame()->coordinatesOf(src); } + +/*! Returns the world coordinates of the point whose position \p src is defined in the Camera +coordinate system. + +cameraCoordinatesOf() performs the inverse transformation. */ +Vec Camera::worldCoordinatesOf(const Vec& src) const { return frame()->inverseCoordinatesOf(src); } + +/*! Returns the fly speed of the Camera. + +Simply returns frame()->flySpeed(). See the ManipulatedCameraFrame::flySpeed() documentation. +This value is only meaningful when the MouseAction bindings is QGLViewer::MOVE_FORWARD or +QGLViewer::MOVE_BACKWARD. + +Set to 1% of the sceneRadius() by setSceneRadius(). See also setFlySpeed(). */ +qreal Camera::flySpeed() const { return frame()->flySpeed(); } + +/*! Sets the Camera flySpeed(). + +\attention This value is modified by setSceneRadius(). */ +void Camera::setFlySpeed(qreal speed) { frame()->setFlySpeed(speed); } + +/*! The point the Camera pivots around with the QGLViewer::ROTATE mouse binding. Defined in world coordinate system. + +Default value is the sceneCenter(). + +\attention setSceneCenter() changes this value. */ +Vec Camera::pivotPoint() const { return frame()->pivotPoint(); } /*! Sets the Camera's position() and orientation() from an OpenGL ModelView matrix. @@ -1150,18 +1293,18 @@ Only the orientation() and position() of the Camera are modified. parameter. */ void Camera::setFromModelViewMatrix(const GLdouble* const modelViewMatrix) { - // Get upper left (rotation) matrix - double upperLeft[3][3]; - for (int i=0; i<3; ++i) - for (int j=0; j<3; ++j) - upperLeft[i][j] = modelViewMatrix[i*4+j]; + // Get upper left (rotation) matrix + qreal upperLeft[3][3]; + for (int i=0; i<3; ++i) + for (int j=0; j<3; ++j) + upperLeft[i][j] = modelViewMatrix[i*4+j]; - // Transform upperLeft into the associated Quaternion - Quaternion q; - q.setFromRotationMatrix(upperLeft); + // Transform upperLeft into the associated Quaternion + Quaternion q; + q.setFromRotationMatrix(upperLeft); - setOrientation(q); - setPosition(-q.rotate(Vec(modelViewMatrix[12], modelViewMatrix[13], modelViewMatrix[14]))); + setOrientation(q); + setPosition(-q.rotate(Vec(modelViewMatrix[12], modelViewMatrix[13], modelViewMatrix[14]))); } /*! Defines the Camera position(), orientation() and fieldOfView() from a projection matrix. @@ -1175,7 +1318,7 @@ void Camera::setFromModelViewMatrix(const GLdouble* const modelViewMatrix) z=0, defined in the Camera coordinate system. The elements of the matrix are ordered in line major order: you can call \c - setFromProjectionMatrix(&(matrix[0][0])) if you defined your matrix as a \c float \c matrix[3][4]. + setFromProjectionMatrix(&(matrix[0][0])) if you defined your matrix as a \c qreal \c matrix[3][4]. \attention Passing the result of getProjectionMatrix() or getModelViewMatrix() to this method is not possible (purposefully incompatible matrix dimensions). \p matrix is more likely to be the @@ -1186,88 +1329,88 @@ void Camera::setFromModelViewMatrix(const GLdouble* const modelViewMatrix) atan(1.0/projectionMatrix[5]). This code was written by Sylvain Paris. */ -void Camera::setFromProjectionMatrix(const float matrix[12]) +void Camera::setFromProjectionMatrix(const qreal matrix[12]) { - // The 3 lines of the matrix are the normals to the planes x=0, y=0, z=0 - // in the camera CS. As we normalize them, we do not need the 4th coordinate. - Vec line_0(matrix[ind(0,0)],matrix[ind(0,1)],matrix[ind(0,2)]); - Vec line_1(matrix[ind(1,0)],matrix[ind(1,1)],matrix[ind(1,2)]); - Vec line_2(matrix[ind(2,0)],matrix[ind(2,1)],matrix[ind(2,2)]); + // The 3 lines of the matrix are the normals to the planes x=0, y=0, z=0 + // in the camera CS. As we normalize them, we do not need the 4th coordinate. + Vec line_0(matrix[ind(0,0)],matrix[ind(0,1)],matrix[ind(0,2)]); + Vec line_1(matrix[ind(1,0)],matrix[ind(1,1)],matrix[ind(1,2)]); + Vec line_2(matrix[ind(2,0)],matrix[ind(2,1)],matrix[ind(2,2)]); - line_0.normalize(); - line_1.normalize(); - line_2.normalize(); + line_0.normalize(); + line_1.normalize(); + line_2.normalize(); - // The camera position is at (0,0,0) in the camera CS so it is the - // intersection of the 3 planes. It can be seen as the kernel - // of the 3x4 projection matrix. We calculate it through 4 dimensional - // vectorial product. We go directly into 3D that is to say we directly - // divide the first 3 coordinates by the 4th one. + // The camera position is at (0,0,0) in the camera CS so it is the + // intersection of the 3 planes. It can be seen as the kernel + // of the 3x4 projection matrix. We calculate it through 4 dimensional + // vectorial product. We go directly into 3D that is to say we directly + // divide the first 3 coordinates by the 4th one. - // We derive the 4 dimensional vectorial product formula from the - // computation of a 4x4 determinant that is developped according to - // its 4th column. This implies some 3x3 determinants. - const Vec cam_pos = Vec(det(matrix[ind(0,1)],matrix[ind(0,2)],matrix[ind(0,3)], - matrix[ind(1,1)],matrix[ind(1,2)],matrix[ind(1,3)], - matrix[ind(2,1)],matrix[ind(2,2)],matrix[ind(2,3)]), + // We derive the 4 dimensional vectorial product formula from the + // computation of a 4x4 determinant that is developped according to + // its 4th column. This implies some 3x3 determinants. + const Vec cam_pos = Vec(det(matrix[ind(0,1)],matrix[ind(0,2)],matrix[ind(0,3)], + matrix[ind(1,1)],matrix[ind(1,2)],matrix[ind(1,3)], + matrix[ind(2,1)],matrix[ind(2,2)],matrix[ind(2,3)]), - -det(matrix[ind(0,0)],matrix[ind(0,2)],matrix[ind(0,3)], - matrix[ind(1,0)],matrix[ind(1,2)],matrix[ind(1,3)], - matrix[ind(2,0)],matrix[ind(2,2)],matrix[ind(2,3)]), + -det(matrix[ind(0,0)],matrix[ind(0,2)],matrix[ind(0,3)], + matrix[ind(1,0)],matrix[ind(1,2)],matrix[ind(1,3)], + matrix[ind(2,0)],matrix[ind(2,2)],matrix[ind(2,3)]), - det(matrix[ind(0,0)],matrix[ind(0,1)],matrix[ind(0,3)], - matrix[ind(1,0)],matrix[ind(1,1)],matrix[ind(1,3)], - matrix[ind(2,0)],matrix[ind(2,1)],matrix[ind(2,3)])) / + det(matrix[ind(0,0)],matrix[ind(0,1)],matrix[ind(0,3)], + matrix[ind(1,0)],matrix[ind(1,1)],matrix[ind(1,3)], + matrix[ind(2,0)],matrix[ind(2,1)],matrix[ind(2,3)])) / - (-det(matrix[ind(0,0)],matrix[ind(0,1)],matrix[ind(0,2)], - matrix[ind(1,0)],matrix[ind(1,1)],matrix[ind(1,2)], - matrix[ind(2,0)],matrix[ind(2,1)],matrix[ind(2,2)])); + (-det(matrix[ind(0,0)],matrix[ind(0,1)],matrix[ind(0,2)], + matrix[ind(1,0)],matrix[ind(1,1)],matrix[ind(1,2)], + matrix[ind(2,0)],matrix[ind(2,1)],matrix[ind(2,2)])); - // We compute the rotation matrix column by column. + // We compute the rotation matrix column by column. - // GL Z axis is front facing. - Vec column_2 = -line_2; + // GL Z axis is front facing. + Vec column_2 = -line_2; - // X-axis is almost like line_0 but should be orthogonal to the Z axis. - Vec column_0 = ((column_2^line_0)^column_2); - column_0.normalize(); + // X-axis is almost like line_0 but should be orthogonal to the Z axis. + Vec column_0 = ((column_2^line_0)^column_2); + column_0.normalize(); - // Y-axis is almost like line_1 but should be orthogonal to the Z axis. - // Moreover line_1 is downward oriented as the screen CS. - Vec column_1 = -((column_2^line_1)^column_2); - column_1.normalize(); + // Y-axis is almost like line_1 but should be orthogonal to the Z axis. + // Moreover line_1 is downward oriented as the screen CS. + Vec column_1 = -((column_2^line_1)^column_2); + column_1.normalize(); - double rot[3][3]; - rot[0][0] = column_0[0]; - rot[1][0] = column_0[1]; - rot[2][0] = column_0[2]; + qreal rot[3][3]; + rot[0][0] = column_0[0]; + rot[1][0] = column_0[1]; + rot[2][0] = column_0[2]; - rot[0][1] = column_1[0]; - rot[1][1] = column_1[1]; - rot[2][1] = column_1[2]; + rot[0][1] = column_1[0]; + rot[1][1] = column_1[1]; + rot[2][1] = column_1[2]; - rot[0][2] = column_2[0]; - rot[1][2] = column_2[1]; - rot[2][2] = column_2[2]; + rot[0][2] = column_2[0]; + rot[1][2] = column_2[1]; + rot[2][2] = column_2[2]; - // We compute the field of view + // We compute the field of view - // line_1^column_0 -> vector of intersection line between - // y_screen=0 and x_camera=0 plane. - // column_2*(...) -> cos of the angle between Z vector et y_screen=0 plane - // * 2 -> field of view = 2 * half angle + // line_1^column_0 -> vector of intersection line between + // y_screen=0 and x_camera=0 plane. + // column_2*(...) -> cos of the angle between Z vector et y_screen=0 plane + // * 2 -> field of view = 2 * half angle - // We need some intermediate values. - Vec dummy = line_1^column_0; - dummy.normalize(); - float fov = acos(column_2*dummy) * 2.0; + // We need some intermediate values. + Vec dummy = line_1^column_0; + dummy.normalize(); + qreal fov = acos(column_2*dummy) * 2.0; - // We set the camera. - Quaternion q; - q.setFromRotationMatrix(rot); - setOrientation(q); - setPosition(cam_pos); - setFieldOfView(fov); + // We set the camera. + Quaternion q; + q.setFromRotationMatrix(rot); + setOrientation(q); + setPosition(cam_pos); + setFieldOfView(fov); } @@ -1277,47 +1420,47 @@ void Camera::setFromProjectionMatrix(const GLdouble* projectionMatrix) { QString message; if ((fabs(projectionMatrix[1]) > 1E-3) || - (fabs(projectionMatrix[2]) > 1E-3) || - (fabs(projectionMatrix[3]) > 1E-3) || - (fabs(projectionMatrix[4]) > 1E-3) || - (fabs(projectionMatrix[6]) > 1E-3) || - (fabs(projectionMatrix[7]) > 1E-3) || - (fabs(projectionMatrix[8]) > 1E-3) || - (fabs(projectionMatrix[9]) > 1E-3)) - message = "Non null coefficient in projection matrix - Aborting"; + (fabs(projectionMatrix[2]) > 1E-3) || + (fabs(projectionMatrix[3]) > 1E-3) || + (fabs(projectionMatrix[4]) > 1E-3) || + (fabs(projectionMatrix[6]) > 1E-3) || + (fabs(projectionMatrix[7]) > 1E-3) || + (fabs(projectionMatrix[8]) > 1E-3) || + (fabs(projectionMatrix[9]) > 1E-3)) + message = "Non null coefficient in projection matrix - Aborting"; else - if ((fabs(projectionMatrix[11]+1.0) < 1E-5) && (fabs(projectionMatrix[15]) < 1E-5)) - { + if ((fabs(projectionMatrix[11]+1.0) < 1E-5) && (fabs(projectionMatrix[15]) < 1E-5)) + { if (projectionMatrix[5] < 1E-4) message="Negative field of view in Camera::setFromProjectionMatrix"; else setType(Camera::PERSPECTIVE); - } - else - if ((fabs(projectionMatrix[11]) < 1E-5) && (fabs(projectionMatrix[15]-1.0) < 1E-5)) + } + else + if ((fabs(projectionMatrix[11]) < 1E-5) && (fabs(projectionMatrix[15]-1.0) < 1E-5)) setType(Camera::ORTHOGRAPHIC); - else + else message = "Unable to determine camera type in setFromProjectionMatrix - Aborting"; if (!message.isEmpty()) - { - qWarning(message); - return; - } + { + qWarning(message); + return; + } switch (type()) - { - case Camera::PERSPECTIVE: - { + { + case Camera::PERSPECTIVE: + { setFieldOfView(2.0 * atan(1.0/projectionMatrix[5])); - const float far = projectionMatrix[14] / (2.0 * (1.0 + projectionMatrix[10])); - const float near = (projectionMatrix[10]+1.0) / (projectionMatrix[10]-1.0) * far; + const qreal far = projectionMatrix[14] / (2.0 * (1.0 + projectionMatrix[10])); + const qreal near = (projectionMatrix[10]+1.0) / (projectionMatrix[10]-1.0) * far; setSceneRadius((far-near)/2.0); setSceneCenter(position() + (near + sceneRadius())*viewDirection()); break; - } - case Camera::ORTHOGRAPHIC: - { + } + case Camera::ORTHOGRAPHIC: + { GLdouble w, h; getOrthoWidthHeight(w,h); projectionMatrix_[0] = 1.0/w; @@ -1328,27 +1471,27 @@ void Camera::setFromProjectionMatrix(const GLdouble* projectionMatrix) projectionMatrix_[15] = 1.0; // same as glOrtho( -w, w, -h, h, zNear(), zFar() ); break; - } - } + } + } } */ ///////////////////////// Camera to world transform /////////////////////// -/*! Same as cameraCoordinatesOf(), but with \c float[3] parameters (\p src and \p res may be identical pointers). */ -void Camera::getCameraCoordinatesOf(const float src[3], float res[3]) const +/*! Same as cameraCoordinatesOf(), but with \c qreal[3] parameters (\p src and \p res may be identical pointers). */ +void Camera::getCameraCoordinatesOf(const qreal src[3], qreal res[3]) const { - Vec r = cameraCoordinatesOf(Vec(src)); - for (int i=0; i<3; ++i) - res[i] = r[i]; + Vec r = cameraCoordinatesOf(Vec(src)); + for (int i=0; i<3; ++i) + res[i] = r[i]; } -/*! Same as worldCoordinatesOf(), but with \c float[3] parameters (\p src and \p res may be identical pointers). */ -void Camera::getWorldCoordinatesOf(const float src[3], float res[3]) const +/*! Same as worldCoordinatesOf(), but with \c qreal[3] parameters (\p src and \p res may be identical pointers). */ +void Camera::getWorldCoordinatesOf(const qreal src[3], qreal res[3]) const { - Vec r = worldCoordinatesOf(Vec(src)); - for (int i=0; i<3; ++i) - res[i] = r[i]; + Vec r = worldCoordinatesOf(Vec(src)); + for (int i=0; i<3; ++i) + res[i] = r[i]; } /*! Fills \p viewport with the Camera OpenGL viewport. @@ -1358,10 +1501,10 @@ Returned values are (0, screenHeight(), screenWidth(), - screenHeight()), so tha located in the \e upper left corner of the window (Qt style coordinate system). */ void Camera::getViewport(GLint viewport[4]) const { - viewport[0] = 0; - viewport[1] = screenHeight(); - viewport[2] = screenWidth(); - viewport[3] = -screenHeight(); + viewport[0] = 0; + viewport[1] = screenHeight(); + viewport[2] = screenWidth(); + viewport[3] = -screenHeight(); } /*! Returns the screen projected coordinates of a point \p src defined in the \p frame coordinate @@ -1388,33 +1531,33 @@ void Camera::getViewport(GLint viewport[4]) const If you call this method several times with no change in the matrices, consider precomputing the projection times modelview matrix to save computation time if required (\c P x \c M in the \c - gluProject man page). + gluProject man page). Here is the code corresponding to what this method does (kindly submitted by Robert W. Kuhn) : \code Vec project(Vec point) { GLint Viewport[4]; - GLdouble Projection[16], Modelview[16]; + GLdouble Projection[16], Modelview[16]; GLdouble matrix[16]; // Precomputation begin glGetIntegerv(GL_VIEWPORT , Viewport); glGetDoublev (GL_MODELVIEW_MATRIX , Modelview); - glGetDoublev (GL_PROJECTION_MATRIX, Projection); + glGetDoublev (GL_PROJECTION_MATRIX, Projection); for (unsigned short m=0; m<4; ++m) { for (unsigned short l=0; l<4; ++l) { - double sum = 0.0; + qreal sum = 0.0; for (unsigned short k=0; k<4; ++k) sum += Projection[l+4*k]*Modelview[k+4*m]; matrix[l+4*m] = sum; } } // Precomputation end - + GLdouble v[4], vs[4]; v[0]=point[0]; v[1]=point[1]; v[2]=point[2]; v[3]=1.0; @@ -1434,33 +1577,38 @@ void Camera::getViewport(GLint viewport[4]) const vs[0] = vs[0] * Viewport[2] + Viewport[0]; vs[1] = vs[1] * Viewport[3] + Viewport[1]; - return Vec(vs[0], Viewport[3]-vs[1], vs[2]); + return Vec(vs[0], Viewport[3]-vs[1], vs[2]); } \endcode */ Vec Camera::projectedCoordinatesOf(const Vec& src, const Frame* frame) const { - GLdouble x,y,z; - static GLint viewport[4]; - getViewport(viewport); + GLdouble x,y,z; + static GLint viewport[4]; + getViewport(viewport); - if (frame) - { - const Vec tmp = frame->inverseCoordinatesOf(src); - gluProject(tmp.x,tmp.y,tmp.z, modelViewMatrix_, projectionMatrix_, viewport, &x,&y,&z); - } - else - gluProject(src.x,src.y,src.z, modelViewMatrix_, projectionMatrix_, viewport, &x,&y,&z); + if (frame) + { + const Vec tmp = frame->inverseCoordinatesOf(src); + gluProject(tmp.x,tmp.y,tmp.z, modelViewMatrix_, projectionMatrix_, viewport, &x,&y,&z); + } + else + gluProject(src.x,src.y,src.z, modelViewMatrix_, projectionMatrix_, viewport, &x,&y,&z); - return Vec(x,y,z); + return Vec(x,y,z); } /*! Returns the world unprojected coordinates of a point \p src defined in the screen coordinate system. The \p src.x and \p src.y input values are expressed in pixels, (0,0) being the \e upper left corner - of the window. \p src.z is a depth value ranging in [0..1[ (near and far plane respectively). See - the \c gluUnProject man page for details. + of the window. \p src.z is a depth value ranging in [0..1[ (respectively corresponding to the near + and far planes). Note that src.z is \e not a linear interpolation between zNear and zFar. + /code + src.z = zFar() / (zFar() - zNear()) * (1.0 - zNear() / z); + /endcode + Where z is the distance from the point you project to the camera, along the viewDirection(). + See the \c gluUnProject man page for details. The result is expressed in the \p frame coordinate system. When \p frame is \c NULL (default), the result is expressed in the world coordinates system. The possible \p frame Frame::referenceFrame() @@ -1482,30 +1630,30 @@ Vec Camera::projectedCoordinatesOf(const Vec& src, const Frame* frame) const viewport) to speed-up the queries. See the \c gluUnProject man page for details. */ Vec Camera::unprojectedCoordinatesOf(const Vec& src, const Frame* frame) const { - GLdouble x,y,z; - static GLint viewport[4]; - getViewport(viewport); - gluUnProject(src.x,src.y,src.z, modelViewMatrix_, projectionMatrix_, viewport, &x,&y,&z); - if (frame) - return frame->coordinatesOf(Vec(x,y,z)); - else - return Vec(x,y,z); + GLdouble x,y,z; + static GLint viewport[4]; + getViewport(viewport); + gluUnProject(src.x,src.y,src.z, modelViewMatrix_, projectionMatrix_, viewport, &x,&y,&z); + if (frame) + return frame->coordinatesOf(Vec(x,y,z)); + else + return Vec(x,y,z); } -/*! Same as projectedCoordinatesOf(), but with \c float parameters (\p src and \p res can be identical pointers). */ -void Camera::getProjectedCoordinatesOf(const float src[3], float res[3], const Frame* frame) const +/*! Same as projectedCoordinatesOf(), but with \c qreal parameters (\p src and \p res can be identical pointers). */ +void Camera::getProjectedCoordinatesOf(const qreal src[3], qreal res[3], const Frame* frame) const { - Vec r = projectedCoordinatesOf(Vec(src), frame); - for (int i=0; i<3; ++i) - res[i] = r[i]; + Vec r = projectedCoordinatesOf(Vec(src), frame); + for (int i=0; i<3; ++i) + res[i] = r[i]; } -/*! Same as unprojectedCoordinatesOf(), but with \c float parameters (\p src and \p res can be identical pointers). */ -void Camera::getUnprojectedCoordinatesOf(const float src[3], float res[3], const Frame* frame) const +/*! Same as unprojectedCoordinatesOf(), but with \c qreal parameters (\p src and \p res can be identical pointers). */ +void Camera::getUnprojectedCoordinatesOf(const qreal src[3], qreal res[3], const Frame* frame) const { - Vec r = unprojectedCoordinatesOf(Vec(src), frame); - for (int i=0; i<3; ++i) - res[i] = r[i]; + Vec r = unprojectedCoordinatesOf(Vec(src), frame); + for (int i=0; i<3; ++i) + res[i] = r[i]; } ///////////////////////////////////// KFI ///////////////////////////////////////// @@ -1513,12 +1661,12 @@ void Camera::getUnprojectedCoordinatesOf(const float src[3], float res[3], const /*! Returns the KeyFrameInterpolator that defines the Camera path number \p i. If path \p i is not defined for this index, the method returns a \c NULL pointer. */ -KeyFrameInterpolator* Camera::keyFrameInterpolator(int i) const +KeyFrameInterpolator* Camera::keyFrameInterpolator(unsigned int i) const { - if (kfi_.contains(i)) - return kfi_[i]; - else - return NULL; + if (kfi_.contains(i)) + return kfi_[i]; + else + return NULL; } /*! Sets the KeyFrameInterpolator that defines the Camera path of index \p i. @@ -1527,24 +1675,24 @@ KeyFrameInterpolator* Camera::keyFrameInterpolator(int i) const needed. The KeyFrameInterpolator::interpolated() signal of \p kfi probably needs to be connected to the - Camera's associated QGLViewer::updateGL() slot, so that when the Camera position is interpolated + Camera's associated QGLViewer::update() slot, so that when the Camera position is interpolated using \p kfi, every interpolation step updates the display: \code myViewer.camera()->deletePath(3); myViewer.camera()->setKeyFrameInterpolator(3, myKeyFrameInterpolator); - connect(myKeyFrameInterpolator, SIGNAL(interpolated()), myViewer, SLOT(updateGL()); + connect(myKeyFrameInterpolator, SIGNAL(interpolated()), myViewer, SLOT(update()); \endcode \note These connections are done automatically when a Camera is attached to a QGLViewer, or when a new KeyFrameInterpolator is defined using the QGLViewer::addKeyFrameKeyboardModifiers() and QGLViewer::pathKey() (default is Alt+F[1-12]). See the keyboard page for details. */ -void Camera::setKeyFrameInterpolator(int i, KeyFrameInterpolator* const kfi) +void Camera::setKeyFrameInterpolator(unsigned int i, KeyFrameInterpolator* const kfi) { - if (kfi) - kfi_[i] = kfi; - else - kfi_.remove(i); + if (kfi) + kfi_[i] = kfi; + else + kfi_.remove(i); } /*! Adds the current Camera position() and orientation() as a keyFrame to the path number \p i. @@ -1558,13 +1706,13 @@ QGLViewer::addKeyFrameKeyboardModifiers(). If you use directly this method and the keyFrameInterpolator(i) does not exist, a new one is created. Its KeyFrameInterpolator::interpolated() signal should then be connected to the -QGLViewer::updateGL() slot (see setKeyFrameInterpolator()). */ -void Camera::addKeyFrameToPath(int i) +QGLViewer::update() slot (see setKeyFrameInterpolator()). */ +void Camera::addKeyFrameToPath(unsigned int i) { - if (!kfi_.contains(i)) - setKeyFrameInterpolator(i, new KeyFrameInterpolator(frame())); + if (!kfi_.contains(i)) + setKeyFrameInterpolator(i, new KeyFrameInterpolator(frame())); - kfi_[i]->addKeyFrame(*(frame())); + kfi_[i]->addKeyFrame(*(frame())); } /*! Makes the Camera follow the path of keyFrameInterpolator() number \p i. @@ -1575,14 +1723,14 @@ void Camera::addKeyFrameToPath(int i) The default keyboard shortcut for this method is F[1-12]. Set QGLViewer::pathKey() and QGLViewer::playPathKeyboardModifiers(). */ -void Camera::playPath(int i) +void Camera::playPath(unsigned int i) { - if (kfi_.contains(i)) { - if (kfi_[i]->interpolationIsStarted()) - kfi_[i]->stopInterpolation(); - else - kfi_[i]->startInterpolation(); - } + if (kfi_.contains(i)) { + if (kfi_[i]->interpolationIsStarted()) + kfi_[i]->stopInterpolation(); + else + kfi_[i]->startInterpolation(); + } } /*! Resets the path of the keyFrameInterpolator() number \p i. @@ -1590,17 +1738,17 @@ void Camera::playPath(int i) If this path is \e not being played (see playPath() and KeyFrameInterpolator::interpolationIsStarted()), resets it to its starting position (see KeyFrameInterpolator::resetInterpolation()). If the path is played, simply stops interpolation. */ -void Camera::resetPath(int i) -{ - if (kfi_.contains(i)) { - if ((kfi_[i]->interpolationIsStarted())) - kfi_[i]->stopInterpolation(); - else - { - kfi_[i]->resetInterpolation(); - kfi_[i]->interpolateAtTime(kfi_[i]->interpolationTime()); - } - } +void Camera::resetPath(unsigned int i) +{ + if (kfi_.contains(i)) { + if ((kfi_[i]->interpolationIsStarted())) + kfi_[i]->stopInterpolation(); + else + { + kfi_[i]->resetInterpolation(); + kfi_[i]->interpolateAtTime(kfi_[i]->interpolationTime()); + } + } } /*! Deletes the keyFrameInterpolator() of index \p i. @@ -1608,17 +1756,17 @@ void Camera::resetPath(int i) Disconnect the keyFrameInterpolator() KeyFrameInterpolator::interpolated() signal before deleting the keyFrameInterpolator() if needed: \code -disconnect(camera()->keyFrameInterpolator(i), SIGNAL(interpolated()), this, SLOT(updateGL())); +disconnect(camera()->keyFrameInterpolator(i), SIGNAL(interpolated()), this, SLOT(update())); camera()->deletePath(i); \endcode */ -void Camera::deletePath(int i) +void Camera::deletePath(unsigned int i) { - if (kfi_.contains(i)) - { - kfi_[i]->stopInterpolation(); - delete kfi_[i]; - kfi_.remove(i); - } + if (kfi_.contains(i)) + { + kfi_[i]->stopInterpolation(); + delete kfi_[i]; + kfi_.remove(i); + } } /*! Draws all the Camera paths defined by the keyFrameInterpolator(). @@ -1629,12 +1777,8 @@ void Camera::deletePath(int i) \attention The OpenGL state is modified by this method: see KeyFrameInterpolator::drawPath(). */ void Camera::drawAllPaths() { - for (QMap::ConstIterator it = kfi_.begin(), end=kfi_.end(); it != end; ++it) -#if QT_VERSION >= 0x040000 - (it.value())->drawPath(3, 5, sceneRadius()); -#else - (it.data())->drawPath(3, 5, sceneRadius()); -#endif + for (QMap::ConstIterator it = kfi_.begin(), end=kfi_.end(); it != end; ++it) + (it.value())->drawPath(3, 5, sceneRadius()); } //////////////////////////////////////////////////////////////////////////////// @@ -1656,53 +1800,49 @@ void Camera::drawAllPaths() QFile f("myCamera.xml"); if (f.open(IO_WriteOnly)) - { - QTextStream out(&f); - document.save(out, 2); - } + { + QTextStream out(&f); + document.save(out, 2); + } \endcode Note that the QGLViewer::camera() is automatically saved by QGLViewer::saveStateToFile() when a QGLViewer is closed. Use QGLViewer::restoreStateFromFile() to restore it back. */ QDomElement Camera::domElement(const QString& name, QDomDocument& document) const { - QDomElement de = document.createElement(name); - QDomElement paramNode = document.createElement("Parameters"); - paramNode.setAttribute("fieldOfView", QString::number(fieldOfView())); - paramNode.setAttribute("zNearCoefficient", QString::number(zNearCoefficient())); - paramNode.setAttribute("zClippingCoefficient", QString::number(zClippingCoefficient())); - paramNode.setAttribute("orthoCoef", QString::number(orthoCoef_)); - paramNode.setAttribute("sceneRadius", QString::number(sceneRadius())); - paramNode.appendChild(sceneCenter().domElement("SceneCenter", document)); + QDomElement de = document.createElement(name); + QDomElement paramNode = document.createElement("Parameters"); + paramNode.setAttribute("fieldOfView", QString::number(fieldOfView())); + paramNode.setAttribute("zNearCoefficient", QString::number(zNearCoefficient())); + paramNode.setAttribute("zClippingCoefficient", QString::number(zClippingCoefficient())); + paramNode.setAttribute("orthoCoef", QString::number(orthoCoef_)); + paramNode.setAttribute("sceneRadius", QString::number(sceneRadius())); + paramNode.appendChild(sceneCenter().domElement("SceneCenter", document)); - switch (type()) - { - case Camera::PERSPECTIVE : paramNode.setAttribute("Type", "PERSPECTIVE"); break; - case Camera::ORTHOGRAPHIC : paramNode.setAttribute("Type", "ORTHOGRAPHIC"); break; - } - de.appendChild(paramNode); - - QDomElement stereoNode = document.createElement("Stereo"); - stereoNode.setAttribute("IODist", QString::number(IODistance())); - stereoNode.setAttribute("focusDistance", QString::number(focusDistance())); - stereoNode.setAttribute("physScreenWidth", QString::number(physicalScreenWidth())); - de.appendChild(stereoNode); - - de.appendChild(frame()->domElement("ManipulatedCameraFrame", document)); - - // KeyFrame paths - for (QMap::ConstIterator it = kfi_.begin(), end=kfi_.end(); it != end; ++it) - { -#if QT_VERSION >= 0x040000 - QDomElement kfNode = (it.value())->domElement("KeyFrameInterpolator", document); -#else - QDomElement kfNode = (it.data())->domElement("KeyFrameInterpolator", document); -#endif - kfNode.setAttribute("index", QString::number(it.key())); - de.appendChild(kfNode); - } + switch (type()) + { + case Camera::PERSPECTIVE : paramNode.setAttribute("Type", "PERSPECTIVE"); break; + case Camera::ORTHOGRAPHIC : paramNode.setAttribute("Type", "ORTHOGRAPHIC"); break; + } + de.appendChild(paramNode); + + QDomElement stereoNode = document.createElement("Stereo"); + stereoNode.setAttribute("IODist", QString::number(IODistance())); + stereoNode.setAttribute("focusDistance", QString::number(focusDistance())); + stereoNode.setAttribute("physScreenWidth", QString::number(physicalScreenWidth())); + de.appendChild(stereoNode); + + de.appendChild(frame()->domElement("ManipulatedCameraFrame", document)); - return de; + // KeyFrame paths + for (QMap::ConstIterator it = kfi_.begin(), end=kfi_.end(); it != end; ++it) + { + QDomElement kfNode = (it.value())->domElement("KeyFrameInterpolator", document); + kfNode.setAttribute("index", QString::number(it.key())); + de.appendChild(kfNode); + } + + return de; } /*! Restores the Camera state from a \c QDomElement created by domElement(). @@ -1728,66 +1868,62 @@ QDomElement Camera::domElement(const QString& name, QDomDocument& document) cons \attention The original keyFrameInterpolator() are deleted and should be copied first if they are shared. */ void Camera::initFromDOMElement(const QDomElement& element) { - QDomElement child=element.firstChild().toElement(); + QDomElement child=element.firstChild().toElement(); -#if QT_VERSION >= 0x040000 - QMutableMapIterator it(kfi_); - while (it.hasNext()) { - it.next(); -#else - for (QMap::Iterator it = kfi_.begin(), end=kfi_.end(); it != end; ++it) { -#endif - deletePath(it.key()); - } + QMutableMapIterator it(kfi_); + while (it.hasNext()) { + it.next(); + deletePath(it.key()); + } - while (!child.isNull()) - { - if (child.tagName() == "Parameters") + while (!child.isNull()) { - // #CONNECTION# Default values set in constructor - setFieldOfView(DomUtils::floatFromDom(child, "fieldOfView", M_PI/4.0f)); - setZNearCoefficient(DomUtils::floatFromDom(child, "zNearCoefficient", 0.005f)); - setZClippingCoefficient(DomUtils::floatFromDom(child, "zClippingCoefficient", sqrt(3.0))); - orthoCoef_ = DomUtils::floatFromDom(child, "orthoCoef", tan(fieldOfView()/2.0)); - setSceneRadius(DomUtils::floatFromDom(child, "sceneRadius", sceneRadius())); - - setType(PERSPECTIVE); - QString type = child.attribute("Type", "PERSPECTIVE"); - if (type == "PERSPECTIVE") setType(Camera::PERSPECTIVE); - if (type == "ORTHOGRAPHIC") setType(Camera::ORTHOGRAPHIC); - - QDomElement child2=child.firstChild().toElement(); - while (!child2.isNull()) - { - /* Although the scene does not change when a camera is loaded, restore the saved center and radius values. - Mainly useful when a the viewer is restored on startup, with possible additional cameras. */ - if (child2.tagName() == "SceneCenter") - setSceneCenter(Vec(child2)); + if (child.tagName() == "Parameters") + { + // #CONNECTION# Default values set in constructor + setFieldOfView(DomUtils::qrealFromDom(child, "fieldOfView", M_PI/4.0)); + setZNearCoefficient(DomUtils::qrealFromDom(child, "zNearCoefficient", 0.005)); + setZClippingCoefficient(DomUtils::qrealFromDom(child, "zClippingCoefficient", sqrt(3.0))); + orthoCoef_ = DomUtils::qrealFromDom(child, "orthoCoef", tan(fieldOfView()/2.0)); + setSceneRadius(DomUtils::qrealFromDom(child, "sceneRadius", sceneRadius())); + + setType(PERSPECTIVE); + QString type = child.attribute("Type", "PERSPECTIVE"); + if (type == "PERSPECTIVE") setType(Camera::PERSPECTIVE); + if (type == "ORTHOGRAPHIC") setType(Camera::ORTHOGRAPHIC); + + QDomElement child2=child.firstChild().toElement(); + while (!child2.isNull()) + { + /* Although the scene does not change when a camera is loaded, restore the saved center and radius values. + Mainly useful when a the viewer is restored on startup, with possible additional cameras. */ + if (child2.tagName() == "SceneCenter") + setSceneCenter(Vec(child2)); + + child2 = child2.nextSibling().toElement(); + } + } - child2 = child2.nextSibling().toElement(); - } - } + if (child.tagName() == "ManipulatedCameraFrame") + frame()->initFromDOMElement(child); - if (child.tagName() == "ManipulatedCameraFrame") - frame()->initFromDOMElement(child); + if (child.tagName() == "Stereo") + { + setIODistance(DomUtils::qrealFromDom(child, "IODist", 0.062)); + setFocusDistance(DomUtils::qrealFromDom(child, "focusDistance", focusDistance())); + setPhysicalScreenWidth(DomUtils::qrealFromDom(child, "physScreenWidth", 0.5)); + } - if (child.tagName() == "Stereo") - { - setIODistance(DomUtils::floatFromDom(child, "IODist", 0.062f)); - setFocusDistance(DomUtils::floatFromDom(child, "focusDistance", focusDistance())); - setPhysicalScreenWidth(DomUtils::floatFromDom(child, "physScreenWidth", 0.5f)); - } + if (child.tagName() == "KeyFrameInterpolator") + { + unsigned int index = DomUtils::uintFromDom(child, "index", 0); + setKeyFrameInterpolator(index, new KeyFrameInterpolator(frame())); + if (keyFrameInterpolator(index)) + keyFrameInterpolator(index)->initFromDOMElement(child); + } - if (child.tagName() == "KeyFrameInterpolator") - { - int index = DomUtils::intFromDom(child, "index", 0); - setKeyFrameInterpolator(index, new KeyFrameInterpolator(frame())); - if (keyFrameInterpolator(index)) - keyFrameInterpolator(index)->initFromDOMElement(child); + child = child.nextSibling().toElement(); } - - child = child.nextSibling().toElement(); - } } /*! Gives the coefficients of a 3D half-line passing through the Camera eye and pixel (x,y). @@ -1803,41 +1939,41 @@ void Camera::initFromDOMElement(const QDomElement& element) See the select example for an illustration. */ void Camera::convertClickToLine(const QPoint& pixel, Vec& orig, Vec& dir) const { - switch (type()) - { - case Camera::PERSPECTIVE: - orig = position(); - dir = Vec( ((2.0 * pixel.x() / screenWidth()) - 1.0) * tan(fieldOfView()/2.0) * aspectRatio(), - ((2.0 * (screenHeight()-pixel.y()) / screenHeight()) - 1.0) * tan(fieldOfView()/2.0), - -1.0 ); - dir = worldCoordinatesOf(dir) - orig; - dir.normalize(); - break; - - case Camera::ORTHOGRAPHIC: - { - GLdouble w,h; - getOrthoWidthHeight(w,h); - orig = Vec((2.0 * pixel.x() / screenWidth() - 1.0)*w, -(2.0 * pixel.y() / screenHeight() - 1.0)*h, 0.0); - orig = worldCoordinatesOf(orig); - dir = viewDirection(); - break; - } - } + switch (type()) + { + case Camera::PERSPECTIVE: + orig = position(); + dir = Vec( ((2.0 * pixel.x() / screenWidth()) - 1.0) * tan(fieldOfView()/2.0) * aspectRatio(), + ((2.0 * (screenHeight()-pixel.y()) / screenHeight()) - 1.0) * tan(fieldOfView()/2.0), + -1.0 ); + dir = worldCoordinatesOf(dir) - orig; + dir.normalize(); + break; + + case Camera::ORTHOGRAPHIC: + { + GLdouble w,h; + getOrthoWidthHeight(w,h); + orig = Vec((2.0 * pixel.x() / screenWidth() - 1.0)*w, -(2.0 * pixel.y() / screenHeight() - 1.0)*h, 0.0); + orig = worldCoordinatesOf(orig); + dir = viewDirection(); + break; + } + } } #ifndef DOXYGEN /*! This method has been deprecated in libQGLViewer version 2.2.0 */ -void Camera::drawCamera(float, float, float) +void Camera::drawCamera(qreal, qreal, qreal) { - qWarning("drawCamera is deprecated. Use Camera::draw() instead."); + qWarning("drawCamera is deprecated. Use Camera::draw() instead."); } #endif /*! Draws a representation of the Camera in the 3D world. The near and far planes are drawn as quads, the frustum is drawn using lines and the camera up -vector is represented by an arrow to disambiguate the drawing. See the +vector is represented by an arrow to disambiguate the drawing. See the standardCamera example for an illustration. Note that the current \c glColor and \c glPolygonMode are used to draw the near and far planes. See @@ -1854,108 +1990,108 @@ The Camera is then correctly positioned and orientated. \note The drawing of a QGLViewer's own QGLViewer::camera() should not be visible, but may create artefacts due to numerical imprecisions. */ -void Camera::draw(bool drawFarPlane, float scale) const +void Camera::draw(bool drawFarPlane, qreal scale) const { - glPushMatrix(); - glMultMatrixd(frame()->worldMatrix()); + glPushMatrix(); + glMultMatrixd(frame()->worldMatrix()); - // 0 is the upper left coordinates of the near corner, 1 for the far one - Vec points[2]; + // 0 is the upper left coordinates of the near corner, 1 for the far one + Vec points[2]; - points[0].z = scale * zNear(); - points[1].z = scale * zFar(); + points[0].z = scale * zNear(); + points[1].z = scale * zFar(); - switch (type()) - { - case Camera::PERSPECTIVE: - { - points[0].y = points[0].z * tan(fieldOfView()/2.0); - points[0].x = points[0].y * aspectRatio(); + switch (type()) + { + case Camera::PERSPECTIVE: + { + points[0].y = points[0].z * tan(fieldOfView()/2.0); + points[0].x = points[0].y * aspectRatio(); - const float ratio = points[1].z / points[0].z; + const qreal ratio = points[1].z / points[0].z; - points[1].y = ratio * points[0].y; - points[1].x = ratio * points[0].x; - break; - } - case Camera::ORTHOGRAPHIC: - { - GLdouble hw, hh; - getOrthoWidthHeight(hw, hh); - points[0].x = points[1].x = scale * float(hw); - points[0].y = points[1].y = scale * float(hh); - break; - } - } - - const int farIndex = drawFarPlane?1:0; - - // Near and (optionally) far plane(s) - glBegin(GL_QUADS); - for (int i=farIndex; i>=0; --i) - { - glNormal3f(0.0, 0.0, (i==0)?1.0:-1.0); - glVertex3f( points[i].x, points[i].y, -points[i].z); - glVertex3f(-points[i].x, points[i].y, -points[i].z); - glVertex3f(-points[i].x, -points[i].y, -points[i].z); - glVertex3f( points[i].x, -points[i].y, -points[i].z); - } - glEnd(); - - // Up arrow - const float arrowHeight = 1.5f * points[0].y; - const float baseHeight = 1.2f * points[0].y; - const float arrowHalfWidth = 0.5f * points[0].x; - const float baseHalfWidth = 0.3f * points[0].x; - - glPolygonMode(GL_FRONT_AND_BACK, GL_FILL); - // Base - glBegin(GL_QUADS); - glVertex3f(-baseHalfWidth, points[0].y, -points[0].z); - glVertex3f( baseHalfWidth, points[0].y, -points[0].z); - glVertex3f( baseHalfWidth, baseHeight, -points[0].z); - glVertex3f(-baseHalfWidth, baseHeight, -points[0].z); - glEnd(); - - // Arrow - glBegin(GL_TRIANGLES); - glVertex3f( 0.0f, arrowHeight, -points[0].z); - glVertex3f(-arrowHalfWidth, baseHeight, -points[0].z); - glVertex3f( arrowHalfWidth, baseHeight, -points[0].z); - glEnd(); - - // Frustum lines - switch (type()) - { - case Camera::PERSPECTIVE : - glBegin(GL_LINES); - glVertex3f(0.0f, 0.0f, 0.0f); - glVertex3f( points[farIndex].x, points[farIndex].y, -points[farIndex].z); - glVertex3f(0.0f, 0.0f, 0.0f); - glVertex3f(-points[farIndex].x, points[farIndex].y, -points[farIndex].z); - glVertex3f(0.0f, 0.0f, 0.0f); - glVertex3f(-points[farIndex].x, -points[farIndex].y, -points[farIndex].z); - glVertex3f(0.0f, 0.0f, 0.0f); - glVertex3f( points[farIndex].x, -points[farIndex].y, -points[farIndex].z); - glEnd(); - break; - case Camera::ORTHOGRAPHIC : - if (drawFarPlane) + points[1].y = ratio * points[0].y; + points[1].x = ratio * points[0].x; + break; + } + case Camera::ORTHOGRAPHIC: + { + GLdouble hw, hh; + getOrthoWidthHeight(hw, hh); + points[0].x = points[1].x = scale * qreal(hw); + points[0].y = points[1].y = scale * qreal(hh); + break; + } + } + + const int farIndex = drawFarPlane?1:0; + + // Near and (optionally) far plane(s) + glBegin(GL_QUADS); + for (int i=farIndex; i>=0; --i) + { + glNormal3d(0.0f, 0.0f, (i==0)?1.0f:-1.0f); + glVertex3d( points[i].x, points[i].y, -points[i].z); + glVertex3d(-points[i].x, points[i].y, -points[i].z); + glVertex3d(-points[i].x, -points[i].y, -points[i].z); + glVertex3d( points[i].x, -points[i].y, -points[i].z); + } + glEnd(); + + // Up arrow + const qreal arrowHeight = 1.5 * points[0].y; + const qreal baseHeight = 1.2 * points[0].y; + const qreal arrowHalfWidth = 0.5 * points[0].x; + const qreal baseHalfWidth = 0.3 * points[0].x; + + glPolygonMode(GL_FRONT_AND_BACK, GL_FILL); + // Base + glBegin(GL_QUADS); + glVertex3d(-baseHalfWidth, points[0].y, -points[0].z); + glVertex3d( baseHalfWidth, points[0].y, -points[0].z); + glVertex3d( baseHalfWidth, baseHeight, -points[0].z); + glVertex3d(-baseHalfWidth, baseHeight, -points[0].z); + glEnd(); + + // Arrow + glBegin(GL_TRIANGLES); + glVertex3d( 0.0, arrowHeight, -points[0].z); + glVertex3d(-arrowHalfWidth, baseHeight, -points[0].z); + glVertex3d( arrowHalfWidth, baseHeight, -points[0].z); + glEnd(); + + // Frustum lines + switch (type()) { - glBegin(GL_LINES); - glVertex3f( points[0].x, points[0].y, -points[0].z); - glVertex3f( points[1].x, points[1].y, -points[1].z); - glVertex3f(-points[0].x, points[0].y, -points[0].z); - glVertex3f(-points[1].x, points[1].y, -points[1].z); - glVertex3f(-points[0].x, -points[0].y, -points[0].z); - glVertex3f(-points[1].x, -points[1].y, -points[1].z); - glVertex3f( points[0].x, -points[0].y, -points[0].z); - glVertex3f( points[1].x, -points[1].y, -points[1].z); - glEnd(); + case Camera::PERSPECTIVE : + glBegin(GL_LINES); + glVertex3d(0.0, 0.0, 0.0); + glVertex3d( points[farIndex].x, points[farIndex].y, -points[farIndex].z); + glVertex3d(0.0, 0.0, 0.0); + glVertex3d(-points[farIndex].x, points[farIndex].y, -points[farIndex].z); + glVertex3d(0.0, 0.0, 0.0); + glVertex3d(-points[farIndex].x, -points[farIndex].y, -points[farIndex].z); + glVertex3d(0.0, 0.0, 0.0); + glVertex3d( points[farIndex].x, -points[farIndex].y, -points[farIndex].z); + glEnd(); + break; + case Camera::ORTHOGRAPHIC : + if (drawFarPlane) + { + glBegin(GL_LINES); + glVertex3d( points[0].x, points[0].y, -points[0].z); + glVertex3d( points[1].x, points[1].y, -points[1].z); + glVertex3d(-points[0].x, points[0].y, -points[0].z); + glVertex3d(-points[1].x, points[1].y, -points[1].z); + glVertex3d(-points[0].x, -points[0].y, -points[0].z); + glVertex3d(-points[1].x, -points[1].y, -points[1].z); + glVertex3d( points[0].x, -points[0].y, -points[0].z); + glVertex3d( points[1].x, -points[1].y, -points[1].z); + glEnd(); + } } - } - glPopMatrix(); + glPopMatrix(); } @@ -1964,7 +2100,7 @@ void Camera::draw(bool drawFarPlane, float scale) const The six 4-component vectors of \p coef respectively correspond to the left, right, near, far, top and bottom Camera frustum planes. Each vector holds a plane equation of the form: \code -a*x + b*y + c*z + d = 0 +a*x + b*y + c*z + d = 0 \endcode where \c a, \c b, \c c and \c d are the 4 components of each vector, in that order. @@ -1984,85 +2120,90 @@ applied in an other viewer to visualize the culling results: \endcode */ void Camera::getFrustumPlanesCoefficients(GLdouble coef[6][4]) const { - // Computed once and for all - const Vec pos = position(); - const Vec viewDir = viewDirection(); - const Vec up = upVector(); - const Vec right = rightVector(); - const float posViewDir = pos * viewDir; + // Computed once and for all + const Vec pos = position(); + const Vec viewDir = viewDirection(); + const Vec up = upVector(); + const Vec right = rightVector(); + const qreal posViewDir = pos * viewDir; - static Vec normal[6]; - static GLdouble dist[6]; - - switch (type()) - { - case Camera::PERSPECTIVE : - { - const float hhfov = horizontalFieldOfView() / 2.0; - const float chhfov = cos(hhfov); - const float shhfov = sin(hhfov); - normal[0] = - shhfov * viewDir; - normal[1] = normal[0] + chhfov * right; - normal[0] = normal[0] - chhfov * right; - + static Vec normal[6]; + static GLdouble dist[6]; + + switch (type()) + { + case Camera::PERSPECTIVE : + { + const qreal hhfov = horizontalFieldOfView() / 2.0; + const qreal chhfov = cos(hhfov); + const qreal shhfov = sin(hhfov); + normal[0] = - shhfov * viewDir; + normal[1] = normal[0] + chhfov * right; + normal[0] = normal[0] - chhfov * right; + + normal[2] = -viewDir; + normal[3] = viewDir; + + const qreal hfov = fieldOfView() / 2.0; + const qreal chfov = cos(hfov); + const qreal shfov = sin(hfov); + normal[4] = - shfov * viewDir; + normal[5] = normal[4] - chfov * up; + normal[4] = normal[4] + chfov * up; + + for (int i=0; i<2; ++i) + dist[i] = pos * normal[i]; + for (int j=4; j<6; ++j) + dist[j] = pos * normal[j]; + + // Natural equations are: + // dist[0,1,4,5] = pos * normal[0,1,4,5]; + // dist[2] = (pos + zNear() * viewDir) * normal[2]; + // dist[3] = (pos + zFar() * viewDir) * normal[3]; + + // 2 times less computations using expanded/merged equations. Dir vectors are normalized. + const qreal posRightCosHH = chhfov * pos * right; + dist[0] = -shhfov * posViewDir; + dist[1] = dist[0] + posRightCosHH; + dist[0] = dist[0] - posRightCosHH; + const qreal posUpCosH = chfov * pos * up; + dist[4] = - shfov * posViewDir; + dist[5] = dist[4] - posUpCosH; + dist[4] = dist[4] + posUpCosH; + + break; + } + case Camera::ORTHOGRAPHIC : + normal[0] = -right; + normal[1] = right; + normal[4] = up; + normal[5] = -up; + + GLdouble hw, hh; + getOrthoWidthHeight(hw, hh); + dist[0] = (pos - hw * right) * normal[0]; + dist[1] = (pos + hw * right) * normal[1]; + dist[4] = (pos + hh * up) * normal[4]; + dist[5] = (pos - hh * up) * normal[5]; + break; + } + + // Front and far planes are identical for both camera types. normal[2] = -viewDir; normal[3] = viewDir; - - const float hfov = fieldOfView() / 2.0; - const float chfov = cos(hfov); - const float shfov = sin(hfov); - normal[4] = - shfov * viewDir; - normal[5] = normal[4] - chfov * up; - normal[4] = normal[4] + chfov * up; - - for (int i=0; i<2; ++i) - dist[i] = pos * normal[i]; - for (int j=4; j<6; ++j) - dist[j] = pos * normal[j]; - - // Natural equations are: - // dist[0,1,4,5] = pos * normal[0,1,4,5]; - // dist[2] = (pos + zNear() * viewDir) * normal[2]; - // dist[3] = (pos + zFar() * viewDir) * normal[3]; - - // 2 times less computations using expanded/merged equations. Dir vectors are normalized. - const float posRightCosHH = chhfov * pos * right; - dist[0] = -shhfov * posViewDir; - dist[1] = dist[0] + posRightCosHH; - dist[0] = dist[0] - posRightCosHH; - const float posUpCosH = chfov * pos * up; - dist[4] = - shfov * posViewDir; - dist[5] = dist[4] - posUpCosH; - dist[4] = dist[4] + posUpCosH; - - break; - } - case Camera::ORTHOGRAPHIC : - normal[0] = -right; - normal[1] = right; - normal[4] = up; - normal[5] = -up; - - GLdouble hw, hh; - getOrthoWidthHeight(hw, hh); - dist[0] = (pos - hw * right) * normal[0]; - dist[1] = (pos + hw * right) * normal[1]; - dist[4] = (pos + hh * up) * normal[4]; - dist[5] = (pos - hh * up) * normal[5]; - break; - } - - // Front and far planes are identical for both camera types. - normal[2] = -viewDir; - normal[3] = viewDir; - dist[2] = -posViewDir - zNear(); - dist[3] = posViewDir + zFar(); - - for (int i=0; i<6; ++i) - { - coef[i][0] = GLdouble(normal[i].x); - coef[i][1] = GLdouble(normal[i].y); - coef[i][2] = GLdouble(normal[i].z); - coef[i][3] = dist[i]; - } + dist[2] = -posViewDir - zNear(); + dist[3] = posViewDir + zFar(); + + for (int i=0; i<6; ++i) + { + coef[i][0] = GLdouble(normal[i].x); + coef[i][1] = GLdouble(normal[i].y); + coef[i][2] = GLdouble(normal[i].z); + coef[i][3] = dist[i]; + } +} + +void Camera::onFrameModified() { + projectionMatrixIsUpToDate_ = false; + modelViewMatrixIsUpToDate_ = false; } diff --git a/octovis/src/extern/QGLViewer/camera.h b/octovis/src/extern/QGLViewer/camera.h index 1f0bf315..4657f952 100644 --- a/octovis/src/extern/QGLViewer/camera.h +++ b/octovis/src/extern/QGLViewer/camera.h @@ -1,8 +1,8 @@ /**************************************************************************** - Copyright (C) 2002-2013 Gilles Debunne. All rights reserved. + Copyright (C) 2002-2014 Gilles Debunne. All rights reserved. - This file is part of the QGLViewer library version 2.4.0. + This file is part of the QGLViewer library version 2.6.3. http://www.libqglviewer.com - contact@libqglviewer.com @@ -23,11 +23,14 @@ #ifndef QGLVIEWER_CAMERA_H #define QGLVIEWER_CAMERA_H -#include "manipulatedCameraFrame.h" #include "keyFrameInterpolator.h" +class QGLViewer; namespace qglviewer { - /*! \brief A perspective or orthographic camera. + +class ManipulatedCameraFrame; + +/*! \brief A perspective or orthographic camera. \class Camera camera.h QGLViewer/camera.h A Camera defines some intrinsic parameters (fieldOfView(), position(), viewDirection(), @@ -49,7 +52,7 @@ namespace qglviewer { The default button binding are: QGLViewer::ROTATE (left), QGLViewer::ZOOM (middle) and QGLViewer::TRANSLATE (right). With this configuration, the Camera \e observes a scene and rotates - around its revolveAroundPoint(). You can switch between this mode and a fly mode using the + around its pivotPoint(). You can switch between this mode and a fly mode using the QGLViewer::CAMERA_MODE (see QGLViewer::toggleCameraMode()) keyboard shortcut (default is 'Space').

Other functionalities

@@ -78,488 +81,431 @@ namespace qglviewer { A Camera can also be used outside of a QGLViewer or even without OpenGL for its coordinate system conversion capabilities. Note however that some of them explicitly rely on the presence of a Z-buffer. \nosubgrouping */ - class QGLVIEWER_EXPORT Camera : public QObject - { +class QGLVIEWER_EXPORT Camera : public QObject +{ #ifndef DOXYGEN - friend class ::QGLViewer; + friend class ::QGLViewer; #endif - Q_OBJECT - - public: - Camera(); - virtual ~Camera(); - - Camera(const Camera& camera); - Camera& operator=(const Camera& camera); - - - /*! Enumerates the two possible types of Camera. - - See type() and setType(). This type mainly defines different Camera projection matrix (see - loadProjectionMatrix()). Many other methods (pointUnderPixel(), convertClickToLine(), - projectedCoordinatesOf(), pixelGLRatio()...) take this Type into account. */ - enum Type { PERSPECTIVE, ORTHOGRAPHIC }; - - /*! @name Position and orientation */ - //@{ - public: - /*! Returns the Camera position (the eye), defined in the world coordinate system. - - Use setPosition() to set the Camera position. Other convenient methods are showEntireScene() or - fitSphere(). Actually returns \c frame()->position(). - - This position corresponds to the projection center of a Camera::PERSPECTIVE Camera. It is not - located in the image plane, which is at a zNear() distance ahead. */ - Vec position() const { return frame()->position(); }; - - /*! Returns the normalized up vector of the Camera, defined in the world coordinate system. + Q_OBJECT - Set using setUpVector() or setOrientation(). It is orthogonal to viewDirection() and to - rightVector(). +public: + Camera(); + virtual ~Camera(); - It corresponds to the Y axis of the associated frame() (actually returns - frame()->inverseTransformOf(Vec(0.0, 1.0, 0.0)) ). */ - Vec upVector() const - { - return frame()->inverseTransformOf(Vec(0.0, 1.0, 0.0)); - } - /*! Returns the normalized view direction of the Camera, defined in the world coordinate system. + Camera(const Camera& camera); + Camera& operator=(const Camera& camera); - Change this value using setViewDirection(), lookAt() or setOrientation(). It is orthogonal to - upVector() and to rightVector(). - This corresponds to the negative Z axis of the frame() ( frame()->inverseTransformOf(Vec(0.0, - 0.0, -1.0)) ). */ - Vec viewDirection() const { return frame()->inverseTransformOf(Vec(0.0, 0.0, -1.0)); }; + /*! Enumerates the two possible types of Camera. - /*! Returns the normalized right vector of the Camera, defined in the world coordinate system. + See type() and setType(). This type mainly defines different Camera projection matrix (see + loadProjectionMatrix()). Many other methods (pointUnderPixel(), convertClickToLine(), + projectedCoordinatesOf(), pixelGLRatio()...) are affected by this Type. */ + enum Type { PERSPECTIVE, ORTHOGRAPHIC }; - This vector lies in the Camera horizontal plane, directed along the X axis (orthogonal to - upVector() and to viewDirection()). Set using setUpVector(), lookAt() or setOrientation(). + /*! @name Position and orientation */ + //@{ +public: + Vec position() const; + Vec upVector() const; + Vec viewDirection() const; + Vec rightVector() const; + Quaternion orientation() const; - Simply returns frame()->inverseTransformOf(Vec(1.0, 0.0, 0.0)). */ - Vec rightVector() const - { - return frame()->inverseTransformOf(Vec(1.0, 0.0, 0.0)); - } + void setFromModelViewMatrix(const GLdouble* const modelViewMatrix); + void setFromProjectionMatrix(const qreal matrix[12]); - /*! Returns the Camera orientation, defined in the world coordinate system. - - Actually returns \c frame()->orientation(). Use setOrientation(), setUpVector() or lookAt() to - set the Camera orientation. */ - Quaternion orientation() const { return frame()->orientation(); }; - - void setFromModelViewMatrix(const GLdouble* const modelViewMatrix); - void setFromProjectionMatrix(const float matrix[12]); - - public Q_SLOTS: - /*! Sets the Camera position() (the eye), defined in the world coordinate system. */ - void setPosition(const Vec& pos) { frame()->setPosition(pos); }; - void setOrientation(const Quaternion& q); - void setOrientation(float theta, float phi); - void setUpVector(const Vec& up, bool noMove=true); - void setViewDirection(const Vec& direction); - //@} +public Q_SLOTS: + void setPosition(const Vec& pos); + void setOrientation(const Quaternion& q); + void setOrientation(qreal theta, qreal phi); + void setUpVector(const Vec& up, bool noMove=true); + void setViewDirection(const Vec& direction); + //@} - /*! @name Positioning tools */ - //@{ - public Q_SLOTS: - void lookAt(const Vec& target); - void showEntireScene(); - void fitSphere(const Vec& center, float radius); - void fitBoundingBox(const Vec& min, const Vec& max); - void fitScreenRegion(const QRect& rectangle); - void centerScene(); - void interpolateToZoomOnPixel(const QPoint& pixel); - void interpolateToFitScene(); - void interpolateTo(const Frame& fr, float duration); - //@} + /*! @name Positioning tools */ + //@{ +public Q_SLOTS: + void lookAt(const Vec& target); + void showEntireScene(); + void fitSphere(const Vec& center, qreal radius); + void fitBoundingBox(const Vec& min, const Vec& max); + void fitScreenRegion(const QRect& rectangle); + void centerScene(); + void interpolateToZoomOnPixel(const QPoint& pixel); + void interpolateToFitScene(); + void interpolateTo(const Frame& fr, qreal duration); + //@} - /*! @name Frustum */ - //@{ - public: - /*! Returns the Camera::Type of the Camera. + /*! @name Frustum */ + //@{ +public: + /*! Returns the Camera::Type of the Camera. - Set by setType(). Mainly used by loadProjectionMatrix(). + Set by setType(). Mainly used by loadProjectionMatrix(). - A Camera::PERSPECTIVE Camera uses a classical projection mainly defined by its fieldOfView(). + A Camera::PERSPECTIVE Camera uses a classical projection mainly defined by its fieldOfView(). - With a Camera::ORTHOGRAPHIC type(), the fieldOfView() is meaningless and the width and height of - the Camera frustum are inferred from the distance to the revolveAroundPoint() using - getOrthoWidthHeight(). + With a Camera::ORTHOGRAPHIC type(), the fieldOfView() is meaningless and the width and height of + the Camera frustum are inferred from the distance to the pivotPoint() using + getOrthoWidthHeight(). - Both types use zNear() and zFar() (to define their clipping planes) and aspectRatio() (for - frustum shape). */ - Type type() const { return type_; }; + Both types use zNear() and zFar() (to define their clipping planes) and aspectRatio() (for + frustum shape). */ + Type type() const { return type_; } - /*! Returns the vertical field of view of the Camera (in radians). + /*! Returns the vertical field of view of the Camera (in radians). - Value is set using setFieldOfView(). Default value is pi/4 radians. This value is meaningless if - the Camera type() is Camera::ORTHOGRAPHIC. + Value is set using setFieldOfView(). Default value is pi/4 radians. This value is meaningless if + the Camera type() is Camera::ORTHOGRAPHIC. - The field of view corresponds the one used in \c gluPerspective (see manual). It sets the Y - (vertical) aperture of the Camera. The X (horizontal) angle is inferred from the window aspect - ratio (see aspectRatio() and horizontalFieldOfView()). + The field of view corresponds the one used in \c gluPerspective (see manual). It sets the Y + (vertical) aperture of the Camera. The X (horizontal) angle is inferred from the window aspect + ratio (see aspectRatio() and horizontalFieldOfView()). - Use setFOVToFitScene() to adapt the fieldOfView() to a given scene. */ - float fieldOfView() const { return fieldOfView_; }; + Use setFOVToFitScene() to adapt the fieldOfView() to a given scene. */ + qreal fieldOfView() const { return fieldOfView_; } - /*! Returns the horizontal field of view of the Camera (in radians). + /*! Returns the horizontal field of view of the Camera (in radians). - Value is set using setHorizontalFieldOfView() or setFieldOfView(). These values - are always linked by: - \code - horizontalFieldOfView() = 2.0 * atan ( tan(fieldOfView()/2.0) * aspectRatio() ). - \endcode */ - float horizontalFieldOfView() const { return 2.0 * atan ( tan(fieldOfView()/2.0) * aspectRatio() ); }; + Value is set using setHorizontalFieldOfView() or setFieldOfView(). These values + are always linked by: + \code + horizontalFieldOfView() = 2.0 * atan ( tan(fieldOfView()/2.0) * aspectRatio() ). + \endcode */ + qreal horizontalFieldOfView() const { return 2.0 * atan ( tan(fieldOfView()/2.0) * aspectRatio() ); } - /*! Returns the Camera aspect ratio defined by screenWidth() / screenHeight(). + /*! Returns the Camera aspect ratio defined by screenWidth() / screenHeight(). - When the Camera is attached to a QGLViewer, these values and hence the aspectRatio() are - automatically fitted to the viewer's window aspect ratio using setScreenWidthAndHeight(). */ - float aspectRatio() const { return static_cast(screenWidth_)/static_cast(screenHeight_); }; - /*! Returns the width (in pixels) of the Camera screen. + When the Camera is attached to a QGLViewer, these values and hence the aspectRatio() are + automatically fitted to the viewer's window aspect ratio using setScreenWidthAndHeight(). */ + qreal aspectRatio() const { return screenWidth_ / static_cast(screenHeight_); } + /*! Returns the width (in pixels) of the Camera screen. - Set using setScreenWidthAndHeight(). This value is automatically fitted to the QGLViewer's - window dimensions when the Camera is attached to a QGLViewer. See also QGLWidget::width() */ - int screenWidth() const { return screenWidth_; }; - /*! Returns the height (in pixels) of the Camera screen. + Set using setScreenWidthAndHeight(). This value is automatically fitted to the QGLViewer's + window dimensions when the Camera is attached to a QGLViewer. See also QGLWidget::width() */ + int screenWidth() const { return screenWidth_; } + /*! Returns the height (in pixels) of the Camera screen. - Set using setScreenWidthAndHeight(). This value is automatically fitted to the QGLViewer's - window dimensions when the Camera is attached to a QGLViewer. See also QGLWidget::height() */ - int screenHeight() const { return screenHeight_; }; - void getViewport(GLint viewport[4]) const; - float pixelGLRatio(const Vec& position) const; + Set using setScreenWidthAndHeight(). This value is automatically fitted to the QGLViewer's + window dimensions when the Camera is attached to a QGLViewer. See also QGLWidget::height() */ + int screenHeight() const { return screenHeight_; } + void getViewport(GLint viewport[4]) const; + qreal pixelGLRatio(const Vec& position) const; - /*! Returns the coefficient which is used to set zNear() when the Camera is inside the sphere - defined by sceneCenter() and zClippingCoefficient() * sceneRadius(). + /*! Returns the coefficient which is used to set zNear() when the Camera is inside the sphere + defined by sceneCenter() and zClippingCoefficient() * sceneRadius(). - In that case, the zNear() value is set to zNearCoefficient() * zClippingCoefficient() * - sceneRadius(). See the zNear() documentation for details. + In that case, the zNear() value is set to zNearCoefficient() * zClippingCoefficient() * + sceneRadius(). See the zNear() documentation for details. - Default value is 0.005, which is appropriate for most applications. In case you need a high - dynamic ZBuffer precision, you can increase this value (~0.1). A lower value will prevent - clipping of very close objects at the expense of a worst Z precision. + Default value is 0.005, which is appropriate for most applications. In case you need a high + dynamic ZBuffer precision, you can increase this value (~0.1). A lower value will prevent + clipping of very close objects at the expense of a worst Z precision. - Only meaningful when Camera type is Camera::PERSPECTIVE. */ - float zNearCoefficient() const { return zNearCoef_; }; - /*! Returns the coefficient used to position the near and far clipping planes. + Only meaningful when Camera type is Camera::PERSPECTIVE. */ + qreal zNearCoefficient() const { return zNearCoef_; } + /*! Returns the coefficient used to position the near and far clipping planes. - The near (resp. far) clipping plane is positioned at a distance equal to zClippingCoefficient() * - sceneRadius() in front of (resp. behind) the sceneCenter(). This garantees an optimal use of - the z-buffer range and minimizes aliasing. See the zNear() and zFar() documentations. + The near (resp. far) clipping plane is positioned at a distance equal to zClippingCoefficient() * + sceneRadius() in front of (resp. behind) the sceneCenter(). This garantees an optimal use of + the z-buffer range and minimizes aliasing. See the zNear() and zFar() documentations. - Default value is square root of 3.0 (so that a cube of size sceneRadius() is not clipped). + Default value is square root of 3.0 (so that a cube of size sceneRadius() is not clipped). - However, since the sceneRadius() is used for other purposes (see showEntireScene(), flySpeed(), - ...) and you may want to change this value to define more precisely the location of the clipping - planes. See also zNearCoefficient(). + However, since the sceneRadius() is used for other purposes (see showEntireScene(), flySpeed(), + ...) and you may want to change this value to define more precisely the location of the clipping + planes. See also zNearCoefficient(). - For a total control on clipping planes' positions, an other option is to overload the zNear() - and zFar() methods. See the standardCamera example. + For a total control on clipping planes' positions, an other option is to overload the zNear() + and zFar() methods. See the standardCamera example. - \attention When QGLViewer::cameraPathAreEdited(), this value is set to 5.0 so that the Camera - paths are not clipped. The previous zClippingCoefficient() value is restored back when you leave - this mode. */ - float zClippingCoefficient() const { return zClippingCoef_; } + \attention When QGLViewer::cameraPathAreEdited(), this value is set to 5.0 so that the Camera + paths are not clipped. The previous zClippingCoefficient() value is restored back when you leave + this mode. */ + qreal zClippingCoefficient() const { return zClippingCoef_; } - virtual float zNear() const; - virtual float zFar() const; - virtual void getOrthoWidthHeight(GLdouble& halfWidth, GLdouble& halfHeight) const; - void getFrustumPlanesCoefficients(GLdouble coef[6][4]) const; + virtual qreal zNear() const; + virtual qreal zFar() const; + virtual void getOrthoWidthHeight(GLdouble& halfWidth, GLdouble& halfHeight) const; + void getFrustumPlanesCoefficients(GLdouble coef[6][4]) const; - public Q_SLOTS: - void setType(Type type); +public Q_SLOTS: + void setType(Type type); - /*! Sets the vertical fieldOfView() of the Camera (in radians). + void setFieldOfView(qreal fov); - Note that focusDistance() is set to sceneRadius() / tan(fieldOfView()/2) by this method. */ - void setFieldOfView(float fov) { fieldOfView_ = fov; setFocusDistance(sceneRadius() / tan(fov/2.0)); }; + /*! Sets the horizontalFieldOfView() of the Camera (in radians). - /*! Sets the horizontalFieldOfView() of the Camera (in radians). + horizontalFieldOfView() and fieldOfView() are linked by the aspectRatio(). This method actually + calls setFieldOfView(( 2.0 * atan (tan(hfov / 2.0) / aspectRatio()) )) so that a call to + horizontalFieldOfView() returns the expected value. */ + void setHorizontalFieldOfView(qreal hfov) { setFieldOfView( 2.0 * atan (tan(hfov / 2.0) / aspectRatio()) ); } - horizontalFieldOfView() and fieldOfView() are linked by the aspectRatio(). This method actually - calls setFieldOfView(( 2.0 * atan (tan(hfov / 2.0) / aspectRatio()) )) so that a call to - horizontalFieldOfView() returns the expected value. */ - void setHorizontalFieldOfView(float hfov) { setFieldOfView( 2.0 * atan (tan(hfov / 2.0) / aspectRatio()) ); }; + void setFOVToFitScene(); - void setFOVToFitScene(); + /*! Defines the Camera aspectRatio(). - /*! Defines the Camera aspectRatio(). + This value is actually inferred from the screenWidth() / screenHeight() ratio. You should use + setScreenWidthAndHeight() instead. - This value is actually inferred from the screenWidth() / screenHeight() ratio. You should use - setScreenWidthAndHeight() instead. + This method might however be convenient when the Camera is not associated with a QGLViewer. It + actually sets the screenHeight() to 100 and the screenWidth() accordingly. See also + setFOVToFitScene(). - This method might however be convenient when the Camera is not associated with a QGLViewer. It - actually sets the screenHeight() to 100 and the screenWidth() accordingly. See also - setFOVToFitScene(). + \note If you absolutely need an aspectRatio() that does not correspond to your viewer's window + dimensions, overload loadProjectionMatrix() or multiply the created GL_PROJECTION matrix by a + scaled diagonal matrix in your QGLViewer::draw() method. */ + void setAspectRatio(qreal aspect) { setScreenWidthAndHeight(int(100.0*aspect), 100); } - \note If you absolutely need an aspectRatio() that does not correspond to your viewer's window - dimensions, overload loadProjectionMatrix() or multiply the created GL_PROJECTION matrix by a - scaled diagonal matrix in your QGLViewer::draw() method. */ - void setAspectRatio(float aspect) { setScreenWidthAndHeight(int(100.0*aspect), 100); }; + void setScreenWidthAndHeight(int width, int height); + /*! Sets the zNearCoefficient() value. */ + void setZNearCoefficient(qreal coef) { zNearCoef_ = coef; projectionMatrixIsUpToDate_ = false; } + /*! Sets the zClippingCoefficient() value. */ + void setZClippingCoefficient(qreal coef) { zClippingCoef_ = coef; projectionMatrixIsUpToDate_ = false; } + //@} - void setScreenWidthAndHeight(int width, int height); - /*! Sets the zNearCoefficient() value. */ - void setZNearCoefficient(float coef) { zNearCoef_ = coef; }; - /*! Sets the zClippingCoefficient() value. */ - void setZClippingCoefficient(float coef) { zClippingCoef_ = coef; } - //@} + /*! @name Scene radius and center */ + //@{ +public: + /*! Returns the radius of the scene observed by the Camera. - /*! @name Scene radius and center */ - //@{ - public: - /*! Returns the radius of the scene observed by the Camera. + You need to provide such an approximation of the scene dimensions so that the Camera can adapt + its zNear() and zFar() values. See the sceneCenter() documentation. - You need to provide such an approximation of the scene dimensions so that the Camera can adapt - its zNear() and zFar() values. See the sceneCenter() documentation. + See also setSceneBoundingBox(). - See also setSceneBoundingBox(). + Note that QGLViewer::sceneRadius() (resp. QGLViewer::setSceneRadius()) simply call this method + (resp. setSceneRadius()) on its associated QGLViewer::camera(). */ + qreal sceneRadius() const { return sceneRadius_; } - Note that QGLViewer::sceneRadius() (resp. QGLViewer::setSceneRadius()) simply call this method - (resp. setSceneRadius()) on its associated QGLViewer::camera(). */ - float sceneRadius() const { return sceneRadius_; }; + /*! Returns the position of the scene center, defined in the world coordinate system. - /*! Returns the position of the scene center, defined in the world coordinate system. + The scene observed by the Camera should be roughly centered on this position, and included in a + sceneRadius() sphere. This approximate description of the scene permits a zNear() and zFar() + clipping planes definition, and allows convenient positioning methods such as showEntireScene(). - The scene observed by the Camera should be roughly centered on this position, and included in a - sceneRadius() sphere. This approximate description of the scene permits a zNear() and zFar() - clipping planes definition, and allows convenient positioning methods such as showEntireScene(). + Default value is (0,0,0) (world origin). Use setSceneCenter() to change it. See also + setSceneBoundingBox(). - Default value is (0,0,0) (world origin). Use setSceneCenter() to change it. See also - setSceneBoundingBox(). + Note that QGLViewer::sceneCenter() (resp. QGLViewer::setSceneCenter()) simply calls this method + (resp. setSceneCenter()) on its associated QGLViewer::camera(). */ + Vec sceneCenter() const { return sceneCenter_; } + qreal distanceToSceneCenter() const; - Note that QGLViewer::sceneCenter() (resp. QGLViewer::setSceneCenter()) simply call this method - (resp. setSceneCenter()) on its associated QGLViewer::camera(). */ - Vec sceneCenter() const { return sceneCenter_; }; - float distanceToSceneCenter() const; +public Q_SLOTS: + void setSceneRadius(qreal radius); + void setSceneCenter(const Vec& center); + bool setSceneCenterFromPixel(const QPoint& pixel); + void setSceneBoundingBox(const Vec& min, const Vec& max); + //@} - public Q_SLOTS: - void setSceneRadius(float radius); - void setSceneCenter(const Vec& center); - bool setSceneCenterFromPixel(const QPoint& pixel); - void setSceneBoundingBox(const Vec& min, const Vec& max); - //@} + /*! @name Pivot Point */ + //@{ +public Q_SLOTS: + void setPivotPoint(const Vec& point); + bool setPivotPointFromPixel(const QPoint& pixel); - /*! @name Revolve Around Point */ - //@{ - public Q_SLOTS: - void setRevolveAroundPoint(const Vec& rap); - bool setRevolveAroundPointFromPixel(const QPoint& pixel); +public: + Vec pivotPoint() const; - public: - /*! The point the Camera revolves around with the QGLViewer::ROTATE mouse binding. Defined in world coordinate system. +#ifndef DOXYGEN +public Q_SLOTS: + void setRevolveAroundPoint(const Vec& point); + bool setRevolveAroundPointFromPixel(const QPoint& pixel); +public: + Vec revolveAroundPoint() const; +#endif + //@} - Default value is the sceneCenter(). - \attention setSceneCenter() changes this value. */ - Vec revolveAroundPoint() const { return frame()->revolveAroundPoint(); }; - //@} + /*! @name Associated frame */ + //@{ +public: + /*! Returns the ManipulatedCameraFrame attached to the Camera. + This ManipulatedCameraFrame defines its position() and orientation() and can translate mouse + events into Camera displacement. Set using setFrame(). */ + ManipulatedCameraFrame* frame() const { return frame_; } +public Q_SLOTS: + void setFrame(ManipulatedCameraFrame* const mcf); + //@} - /*! @name Associated frame */ - //@{ - public: - /*! Returns the ManipulatedCameraFrame attached to the Camera. - This ManipulatedCameraFrame defines its position() and orientation() and can translate mouse - events into Camera displacement. Set using setFrame(). */ - ManipulatedCameraFrame* frame() const { return frame_; }; - public Q_SLOTS: - void setFrame(ManipulatedCameraFrame* const mcf); - //@} + /*! @name KeyFramed paths */ + //@{ +public: + KeyFrameInterpolator* keyFrameInterpolator(unsigned int i) const; +public Q_SLOTS: + void setKeyFrameInterpolator(unsigned int i, KeyFrameInterpolator* const kfi); - /*! @name KeyFramed paths */ - //@{ - public: - KeyFrameInterpolator* keyFrameInterpolator(int i) const; + virtual void addKeyFrameToPath(unsigned int i); + virtual void playPath(unsigned int i); + virtual void deletePath(unsigned int i); + virtual void resetPath(unsigned int i); + virtual void drawAllPaths(); + //@} -public Q_SLOTS: - void setKeyFrameInterpolator(int i, KeyFrameInterpolator* const kfi); - virtual void addKeyFrameToPath(int i); - virtual void playPath(int i); - virtual void deletePath(int i); - virtual void resetPath(int i); - virtual void drawAllPaths(); - //@} + /*! @name OpenGL matrices */ + //@{ +public: + virtual void loadProjectionMatrix(bool reset=true) const; + virtual void loadModelViewMatrix(bool reset=true) const; + void computeProjectionMatrix() const; + void computeModelViewMatrix() const; + virtual void loadProjectionMatrixStereo(bool leftBuffer=true) const; + virtual void loadModelViewMatrixStereo(bool leftBuffer=true) const; - /*! @name OpenGL matrices */ - //@{ - public: - virtual void loadProjectionMatrix(bool reset=true) const; - virtual void loadModelViewMatrix(bool reset=true) const; - void computeProjectionMatrix() const; - void computeModelViewMatrix() const; + void getProjectionMatrix(GLfloat m[16]) const; + void getProjectionMatrix(GLdouble m[16]) const; - virtual void loadProjectionMatrixStereo(bool leftBuffer=true) const; - virtual void loadModelViewMatrixStereo(bool leftBuffer=true) const; + void getModelViewMatrix(GLfloat m[16]) const; + void getModelViewMatrix(GLdouble m[16]) const; - void getProjectionMatrix(GLdouble m[16]) const; - void getModelViewMatrix(GLdouble m[16]) const; + void getModelViewProjectionMatrix(GLfloat m[16]) const; void getModelViewProjectionMatrix(GLdouble m[16]) const; + //@} -#ifndef DOXYGEN - // Required for windows which otherwise silently fills - void getProjectionMatrix(GLfloat m[16]) const; - void getModelViewMatrix(GLfloat m[16]) const; -#endif - //@} - - /*! @name Drawing */ - //@{ + /*! @name Drawing */ + //@{ #ifndef DOXYGEN - static void drawCamera(float scale=1.0, float aspectRatio=1.33, float fieldOfView=M_PI/4.0); + static void drawCamera(qreal scale=1.0, qreal aspectRatio=1.33, qreal fieldOfView=qreal(M_PI)/4.0); #endif - virtual void draw(bool drawFarPlane=true, float scale=1.0) const; - //@} - - - /*! @name World to Camera coordinate systems conversions */ - //@{ - public: - /*! Returns the Camera frame coordinates of a point \p src defined in world coordinates. - - worldCoordinatesOf() performs the inverse transformation. - - Note that the point coordinates are simply converted in a different coordinate system. They are - not projected on screen. Use projectedCoordinatesOf() for that. */ - Vec cameraCoordinatesOf(const Vec& src) const { return frame()->coordinatesOf(src); }; - /*! Returns the world coordinates of the point whose position \p src is defined in the Camera - coordinate system. - - cameraCoordinatesOf() performs the inverse transformation. */ - Vec worldCoordinatesOf(const Vec& src) const { return frame()->inverseCoordinatesOf(src); }; - void getCameraCoordinatesOf(const float src[3], float res[3]) const; - void getWorldCoordinatesOf(const float src[3], float res[3]) const; - //@} - - - /*! @name 2D screen to 3D world coordinate systems conversions */ - //@{ - public: - Vec projectedCoordinatesOf(const Vec& src, const Frame* frame=NULL) const; - Vec unprojectedCoordinatesOf(const Vec& src, const Frame* frame=NULL) const; - void getProjectedCoordinatesOf(const float src[3], float res[3], const Frame* frame=NULL) const; - void getUnprojectedCoordinatesOf(const float src[3], float res[3], const Frame* frame=NULL) const; - void convertClickToLine(const QPoint& pixel, Vec& orig, Vec& dir) const; - Vec pointUnderPixel(const QPoint& pixel, bool& found) const; - //@} - - - /*! @name Fly speed */ - //@{ - public: - /*! Returns the fly speed of the Camera. - - Simply returns frame()->flySpeed(). See the ManipulatedCameraFrame::flySpeed() documentation. - This value is only meaningful when the MouseAction bindings is QGLViewer::MOVE_FORWARD or - QGLViewer::MOVE_BACKWARD. - - Set to 1% of the sceneRadius() by setSceneRadius(). See also setFlySpeed(). */ - float flySpeed() const { return frame()->flySpeed(); }; - public Q_SLOTS: - /*! Sets the Camera flySpeed(). - - \attention This value is modified by setSceneRadius(). */ - void setFlySpeed(float speed) { frame()->setFlySpeed(speed); }; - //@} + virtual void draw(bool drawFarPlane=true, qreal scale=1.0) const; + //@} + + + /*! @name World to Camera coordinate systems conversions */ + //@{ +public: + Vec cameraCoordinatesOf(const Vec& src) const; + Vec worldCoordinatesOf(const Vec& src) const; + void getCameraCoordinatesOf(const qreal src[3], qreal res[3]) const; + void getWorldCoordinatesOf(const qreal src[3], qreal res[3]) const; + //@} + + + /*! @name 2D screen to 3D world coordinate systems conversions */ + //@{ +public: + Vec projectedCoordinatesOf(const Vec& src, const Frame* frame=NULL) const; + Vec unprojectedCoordinatesOf(const Vec& src, const Frame* frame=NULL) const; + void getProjectedCoordinatesOf(const qreal src[3], qreal res[3], const Frame* frame=NULL) const; + void getUnprojectedCoordinatesOf(const qreal src[3], qreal res[3], const Frame* frame=NULL) const; + void convertClickToLine(const QPoint& pixel, Vec& orig, Vec& dir) const; + Vec pointUnderPixel(const QPoint& pixel, bool& found) const; + //@} + + + /*! @name Fly speed */ + //@{ +public: + qreal flySpeed() const; +public Q_SLOTS: + void setFlySpeed(qreal speed); + //@} - /*! @name Stereo parameters */ - //@{ - public: - /*! Returns the user's inter-ocular distance (in meters). Default value is 0.062m, which fits most people. + /*! @name Stereo parameters */ + //@{ +public: + /*! Returns the user's inter-ocular distance (in meters). Default value is 0.062m, which fits most people. - loadProjectionMatrixStereo() uses this value to define the Camera offset and frustum. See - setIODistance(). */ - float IODistance() const { return IODistance_; }; + loadProjectionMatrixStereo() uses this value to define the Camera offset and frustum. See + setIODistance(). */ + qreal IODistance() const { return IODistance_; } - /*! Returns the physical distance between the user's eyes and the screen (in meters). + /*! Returns the physical distance between the user's eyes and the screen (in meters). - physicalDistanceToScreen() and focusDistance() represent the same distance. The former is - expressed in physical real world units, while the latter is expressed in OpenGL virtual world - units. + physicalDistanceToScreen() and focusDistance() represent the same distance. The former is + expressed in physical real world units, while the latter is expressed in OpenGL virtual world + units. This is a helper function. It simply returns physicalScreenWidth() / 2.0 / tan(horizontalFieldOfView() / 2.0); */ - float physicalDistanceToScreen() const { return physicalScreenWidth() / 2.0f / tan(horizontalFieldOfView() / 2.0); }; + qreal physicalDistanceToScreen() const { return physicalScreenWidth() / 2.0 / tan(horizontalFieldOfView() / 2.0); } - /*! Returns the physical screen width, in meters. Default value is 0.5m (average monitor width). + /*! Returns the physical screen width, in meters. Default value is 0.5m (average monitor width). - Used for stereo display only (see loadModelViewMatrixStereo() and loadProjectionMatrixStereo()). - Set using setPhysicalScreenWidth(). */ - float physicalScreenWidth() const { return physicalScreenWidth_; }; + Used for stereo display only (see loadModelViewMatrixStereo() and loadProjectionMatrixStereo()). + Set using setPhysicalScreenWidth(). */ + qreal physicalScreenWidth() const { return physicalScreenWidth_; } - /*! Returns the focus distance used by stereo display, expressed in OpenGL units. + /*! Returns the focus distance used by stereo display, expressed in OpenGL units. - This is the distance in the virtual world between the Camera and the plane where the horizontal - stereo parallax is null (the stereo left and right cameras' lines of sigth cross at this distance). + This is the distance in the virtual world between the Camera and the plane where the horizontal + stereo parallax is null (the stereo left and right cameras' lines of sigth cross at this distance). - This distance is the virtual world equivalent of the real-world physicalDistanceToScreen(). + This distance is the virtual world equivalent of the real-world physicalDistanceToScreen(). - \attention This value is modified by QGLViewer::setSceneRadius(), setSceneRadius() and - setFieldOfView(). When one of these values is modified, focusDistance() is set to sceneRadius() - / tan(fieldOfView()/2), which provides good results. */ - float focusDistance() const { return focusDistance_; }; - public Q_SLOTS: - /*! Sets the IODistance(). */ - void setIODistance(float distance) { IODistance_ = distance; }; + \attention This value is modified by QGLViewer::setSceneRadius(), setSceneRadius() and + setFieldOfView(). When one of these values is modified, focusDistance() is set to sceneRadius() + / tan(fieldOfView()/2), which provides good results. */ + qreal focusDistance() const { return focusDistance_; } +public Q_SLOTS: + /*! Sets the IODistance(). */ + void setIODistance(qreal distance) { IODistance_ = distance; } #ifndef DOXYGEN /*! This method is deprecated. Use setPhysicalScreenWidth() instead. */ - void setPhysicalDistanceToScreen(float distance) { Q_UNUSED(distance); qWarning("setPhysicalDistanceToScreen is deprecated, use setPhysicalScreenWidth instead"); }; + void setPhysicalDistanceToScreen(qreal distance) { Q_UNUSED(distance); qWarning("setPhysicalDistanceToScreen is deprecated, use setPhysicalScreenWidth instead"); } #endif - /*! Sets the physical screen (monitor or projected wall) width (in meters). */ - void setPhysicalScreenWidth(float width) { physicalScreenWidth_ = width; }; - - /*! Sets the focusDistance(), in OpenGL scene units. */ - void setFocusDistance(float distance) { focusDistance_ = distance; }; - //@} - - - /*! @name XML representation */ - //@{ - public: - virtual QDomElement domElement(const QString& name, QDomDocument& document) const; - public Q_SLOTS: - virtual void initFromDOMElement(const QDomElement& element); - //@} - - - private: - // F r a m e - ManipulatedCameraFrame* frame_; - - // C a m e r a p a r a m e t e r s - int screenWidth_, screenHeight_; // size of the window, in pixels - float fieldOfView_; // in radians - Vec sceneCenter_; - float sceneRadius_; // OpenGL units - float zNearCoef_; - float zClippingCoef_; - float orthoCoef_; - Type type_; // PERSPECTIVE or ORTHOGRAPHIC - mutable GLdouble modelViewMatrix_[16]; // Buffered model view matrix. - mutable GLdouble projectionMatrix_[16]; // Buffered projection matrix. - - // S t e r e o p a r a m e t e r s - float IODistance_; // inter-ocular distance, in meters - float focusDistance_; // in scene units - float physicalScreenWidth_; // in meters - - // P o i n t s o f V i e w s a n d K e y F r a m e s - QMap kfi_; - KeyFrameInterpolator* interpolationKfi_; - }; + /*! Sets the physical screen (monitor or projected wall) width (in meters). */ + void setPhysicalScreenWidth(qreal width) { physicalScreenWidth_ = width; } + + /*! Sets the focusDistance(), in OpenGL scene units. */ + void setFocusDistance(qreal distance) { focusDistance_ = distance; } + //@} + + + /*! @name XML representation */ + //@{ +public: + virtual QDomElement domElement(const QString& name, QDomDocument& document) const; +public Q_SLOTS: + virtual void initFromDOMElement(const QDomElement& element); + //@} + + +private Q_SLOTS: + void onFrameModified(); + +private: + // F r a m e + ManipulatedCameraFrame* frame_; + + // C a m e r a p a r a m e t e r s + int screenWidth_, screenHeight_; // size of the window, in pixels + qreal fieldOfView_; // in radians + Vec sceneCenter_; + qreal sceneRadius_; // OpenGL units + qreal zNearCoef_; + qreal zClippingCoef_; + qreal orthoCoef_; + Type type_; // PERSPECTIVE or ORTHOGRAPHIC + mutable GLdouble modelViewMatrix_[16]; // Buffered model view matrix. + mutable bool modelViewMatrixIsUpToDate_; + mutable GLdouble projectionMatrix_[16]; // Buffered projection matrix. + mutable bool projectionMatrixIsUpToDate_; + + // S t e r e o p a r a m e t e r s + qreal IODistance_; // inter-ocular distance, in meters + qreal focusDistance_; // in scene units + qreal physicalScreenWidth_; // in meters + + // P o i n t s o f V i e w s a n d K e y F r a m e s + QMap kfi_; + KeyFrameInterpolator* interpolationKfi_; +}; } // namespace qglviewer diff --git a/octovis/src/extern/QGLViewer/config.h b/octovis/src/extern/QGLViewer/config.h index a772e418..dbe1cfa0 100644 --- a/octovis/src/extern/QGLViewer/config.h +++ b/octovis/src/extern/QGLViewer/config.h @@ -1,8 +1,8 @@ /**************************************************************************** - Copyright (C) 2002-2013 Gilles Debunne. All rights reserved. + Copyright (C) 2002-2014 Gilles Debunne. All rights reserved. - This file is part of the QGLViewer library version 2.4.0. + This file is part of the QGLViewer library version 2.6.3. http://www.libqglviewer.com - contact@libqglviewer.com @@ -28,7 +28,7 @@ #ifndef QGLVIEWER_CONFIG_H #define QGLVIEWER_CONFIG_H -#define QGLVIEWER_VERSION 0x020400 +#define QGLVIEWER_VERSION 0x020603 // Needed for Qt < 4 (?) #ifndef QT_CLEAN_NAMESPACE @@ -38,16 +38,14 @@ // Get QT_VERSION and other Qt flags #include -#if QT_VERSION < 0x030000 -# ifdef _OS_WIN32_ -# define Q_OS_WIN32 -# endif +#if QT_VERSION < 0x040000 +Error : libQGLViewer requires a minimum Qt version of 4.0 #endif // Win 32 DLL export macros #ifdef Q_OS_WIN32 # ifndef M_PI -# define M_PI 3.14159265358979323846f +# define M_PI 3.14159265358979323846 # endif # ifndef QGLVIEWER_STATIC # ifdef CREATE_QGLVIEWER_DLL @@ -76,50 +74,19 @@ #endif // OpenGL includes - Included here and hence shared by all the files that need OpenGL headers. -#if QT_VERSION >= 0x040000 # include -#else -# include -#endif -// GLU was removed from Qt in version 4.8 +// GLU was removed from Qt in version 4.8 #ifdef Q_OS_MAC # include #else # include #endif -// Old Qt versions require GLUT for text rendering -#define QGLVIEWER_QT_VERSION_WITHOUT_GLUT 0x030100 -#if QT_VERSION < QGLVIEWER_QT_VERSION_WITHOUT_GLUT -# ifdef Q_OS_MAC -# include -# else -# ifdef Q_OS_WIN32 -# include -# else -# include -# endif -# endif -#endif - // Container classes interfaces changed a lot in Qt. // Compatibility patches are all grouped here. -#if QT_VERSION >= 0x040000 -# include -# include -#else -# define qMax(a,b) QMAX(a,b) -# include -# include -#endif - -// Support for the no_keywords CONFIG option on previous Qt versions -#if QT_VERSION < 0x040400 -# define Q_SLOTS slots -# define Q_SIGNALS signals -# define Q_EMIT emit -#endif +#include +#include // For deprecated methods // #define __WHERE__ "In file "<<__FILE__<<", line "<<__LINE__<<": " diff --git a/octovis/src/extern/QGLViewer/constraint.cpp b/octovis/src/extern/QGLViewer/constraint.cpp index ef5ebbbf..fbb9a6c2 100644 --- a/octovis/src/extern/QGLViewer/constraint.cpp +++ b/octovis/src/extern/QGLViewer/constraint.cpp @@ -1,8 +1,8 @@ /**************************************************************************** - Copyright (C) 2002-2013 Gilles Debunne. All rights reserved. + Copyright (C) 2002-2014 Gilles Debunne. All rights reserved. - This file is part of the QGLViewer library version 2.4.0. + This file is part of the QGLViewer library version 2.6.3. http://www.libqglviewer.com - contact@libqglviewer.com @@ -23,6 +23,7 @@ #include "constraint.h" #include "frame.h" #include "camera.h" +#include "manipulatedCameraFrame.h" using namespace qglviewer; using namespace std; @@ -36,55 +37,55 @@ using namespace std; translationConstraintType() and rotationConstraintType() are set to AxisPlaneConstraint::FREE. translationConstraintDirection() and rotationConstraintDirection() are set to (0,0,0). */ AxisPlaneConstraint::AxisPlaneConstraint() - : translationConstraintType_(FREE), rotationConstraintType_(FREE) + : translationConstraintType_(FREE), rotationConstraintType_(FREE) { - // Do not use set since setRotationConstraintType needs a read. + // Do not use set since setRotationConstraintType needs a read. } /*! Simply calls setTranslationConstraintType() and setTranslationConstraintDirection(). */ void AxisPlaneConstraint::setTranslationConstraint(Type type, const Vec& direction) { - setTranslationConstraintType(type); - setTranslationConstraintDirection(direction); + setTranslationConstraintType(type); + setTranslationConstraintDirection(direction); } /*! Defines the translationConstraintDirection(). The coordinate system where \p direction is expressed depends on your class implementation. */ void AxisPlaneConstraint::setTranslationConstraintDirection(const Vec& direction) { - if ((translationConstraintType()!=AxisPlaneConstraint::FREE) && (translationConstraintType()!=AxisPlaneConstraint::FORBIDDEN)) - { - const float norm = direction.norm(); - if (norm < 1E-8) + if ((translationConstraintType()!=AxisPlaneConstraint::FREE) && (translationConstraintType()!=AxisPlaneConstraint::FORBIDDEN)) { - qWarning("AxisPlaneConstraint::setTranslationConstraintDir: null vector for translation constraint"); - translationConstraintType_ = AxisPlaneConstraint::FREE; + const qreal norm = direction.norm(); + if (norm < 1E-8) + { + qWarning("AxisPlaneConstraint::setTranslationConstraintDir: null vector for translation constraint"); + translationConstraintType_ = AxisPlaneConstraint::FREE; + } + else + translationConstraintDir_ = direction/norm; } - else - translationConstraintDir_ = direction/norm; - } } /*! Simply calls setRotationConstraintType() and setRotationConstraintDirection(). */ void AxisPlaneConstraint::setRotationConstraint(Type type, const Vec& direction) { - setRotationConstraintType(type); - setRotationConstraintDirection(direction); + setRotationConstraintType(type); + setRotationConstraintDirection(direction); } /*! Defines the rotationConstraintDirection(). The coordinate system where \p direction is expressed depends on your class implementation. */ void AxisPlaneConstraint::setRotationConstraintDirection(const Vec& direction) { - if ((rotationConstraintType()!=AxisPlaneConstraint::FREE) && (rotationConstraintType()!=AxisPlaneConstraint::FORBIDDEN)) - { - float norm = direction.norm(); - if (norm < 1E-8) + if ((rotationConstraintType()!=AxisPlaneConstraint::FREE) && (rotationConstraintType()!=AxisPlaneConstraint::FORBIDDEN)) { - qWarning("AxisPlaneConstraint::setRotationConstraintDir: null vector for rotation constraint"); - rotationConstraintType_ = AxisPlaneConstraint::FREE; + const qreal norm = direction.norm(); + if (norm < 1E-8) + { + qWarning("AxisPlaneConstraint::setRotationConstraintDir: null vector for rotation constraint"); + rotationConstraintType_ = AxisPlaneConstraint::FREE; + } + else + rotationConstraintDir_ = direction/norm; } - else - rotationConstraintDir_ = direction/norm; - } } /*! Set the Type() of the rotationConstraintType(). Default is AxisPlaneConstraint::FREE. @@ -100,13 +101,13 @@ void AxisPlaneConstraint::setRotationConstraintDirection(const Vec& direction) will be ignored. */ void AxisPlaneConstraint::setRotationConstraintType(Type type) { - if (rotationConstraintType() == AxisPlaneConstraint::PLANE) - { - qWarning("AxisPlaneConstraint::setRotationConstraintType: the PLANE type cannot be used for a rotation constraints"); - return; - } + if (rotationConstraintType() == AxisPlaneConstraint::PLANE) + { + qWarning("AxisPlaneConstraint::setRotationConstraintType: the PLANE type cannot be used for a rotation constraints"); + return; + } - rotationConstraintType_ = type; + rotationConstraintType_ = type; } @@ -119,23 +120,23 @@ void AxisPlaneConstraint::setRotationConstraintType(Type type) translationConstraintDirection(). */ void LocalConstraint::constrainTranslation(Vec& translation, Frame* const frame) { - Vec proj; - switch (translationConstraintType()) - { - case AxisPlaneConstraint::FREE: - break; - case AxisPlaneConstraint::PLANE: - proj = frame->rotation().rotate(translationConstraintDirection()); - translation.projectOnPlane(proj); - break; - case AxisPlaneConstraint::AXIS: - proj = frame->rotation().rotate(translationConstraintDirection()); - translation.projectOnAxis(proj); - break; - case AxisPlaneConstraint::FORBIDDEN: - translation = Vec(0.0, 0.0, 0.0); - break; - } + Vec proj; + switch (translationConstraintType()) + { + case AxisPlaneConstraint::FREE: + break; + case AxisPlaneConstraint::PLANE: + proj = frame->rotation().rotate(translationConstraintDirection()); + translation.projectOnPlane(proj); + break; + case AxisPlaneConstraint::AXIS: + proj = frame->rotation().rotate(translationConstraintDirection()); + translation.projectOnAxis(proj); + break; + case AxisPlaneConstraint::FORBIDDEN: + translation = Vec(0.0, 0.0, 0.0); + break; + } } /*! When rotationConstraintType() is AxisPlaneConstraint::AXIS, constrain \p rotation to be a rotation @@ -143,24 +144,24 @@ void LocalConstraint::constrainTranslation(Vec& translation, Frame* const frame) rotationConstraintDirection(). */ void LocalConstraint::constrainRotation(Quaternion& rotation, Frame* const) { - switch (rotationConstraintType()) - { - case AxisPlaneConstraint::FREE: - break; - case AxisPlaneConstraint::PLANE: - break; - case AxisPlaneConstraint::AXIS: - { - Vec axis = rotationConstraintDirection(); - Vec quat = Vec(rotation[0], rotation[1], rotation[2]); - quat.projectOnAxis(axis); - rotation = Quaternion(quat, 2.0*acos(rotation[3])); - } - break; - case AxisPlaneConstraint::FORBIDDEN: - rotation = Quaternion(); // identity - break; - } + switch (rotationConstraintType()) + { + case AxisPlaneConstraint::FREE: + break; + case AxisPlaneConstraint::PLANE: + break; + case AxisPlaneConstraint::AXIS: + { + Vec axis = rotationConstraintDirection(); + Vec quat = Vec(rotation[0], rotation[1], rotation[2]); + quat.projectOnAxis(axis); + rotation = Quaternion(quat, 2.0*acos(rotation[3])); + } + break; + case AxisPlaneConstraint::FORBIDDEN: + rotation = Quaternion(); // identity + break; + } } //////////////////////////////////////////////////////////////////////////////// @@ -172,33 +173,33 @@ void LocalConstraint::constrainRotation(Quaternion& rotation, Frame* const) translationConstraintDirection(). */ void WorldConstraint::constrainTranslation(Vec& translation, Frame* const frame) { - Vec proj; - switch (translationConstraintType()) - { - case AxisPlaneConstraint::FREE: - break; - case AxisPlaneConstraint::PLANE: - if (frame->referenceFrame()) - { - proj = frame->referenceFrame()->transformOf(translationConstraintDirection()); - translation.projectOnPlane(proj); - } - else - translation.projectOnPlane(translationConstraintDirection()); - break; - case AxisPlaneConstraint::AXIS: - if (frame->referenceFrame()) + Vec proj; + switch (translationConstraintType()) { - proj = frame->referenceFrame()->transformOf(translationConstraintDirection()); - translation.projectOnAxis(proj); + case AxisPlaneConstraint::FREE: + break; + case AxisPlaneConstraint::PLANE: + if (frame->referenceFrame()) + { + proj = frame->referenceFrame()->transformOf(translationConstraintDirection()); + translation.projectOnPlane(proj); + } + else + translation.projectOnPlane(translationConstraintDirection()); + break; + case AxisPlaneConstraint::AXIS: + if (frame->referenceFrame()) + { + proj = frame->referenceFrame()->transformOf(translationConstraintDirection()); + translation.projectOnAxis(proj); + } + else + translation.projectOnAxis(translationConstraintDirection()); + break; + case AxisPlaneConstraint::FORBIDDEN: + translation = Vec(0.0, 0.0, 0.0); + break; } - else - translation.projectOnAxis(translationConstraintDirection()); - break; - case AxisPlaneConstraint::FORBIDDEN: - translation = Vec(0.0, 0.0, 0.0); - break; - } } /*! When rotationConstraintType() is AxisPlaneConstraint::AXIS, constrain \p rotation to be a rotation @@ -206,24 +207,24 @@ void WorldConstraint::constrainTranslation(Vec& translation, Frame* const frame) rotationConstraintDirection(). */ void WorldConstraint::constrainRotation(Quaternion& rotation, Frame* const frame) { - switch (rotationConstraintType()) - { - case AxisPlaneConstraint::FREE: - break; - case AxisPlaneConstraint::PLANE: - break; - case AxisPlaneConstraint::AXIS: - { - Vec quat(rotation[0], rotation[1], rotation[2]); - Vec axis = frame->transformOf(rotationConstraintDirection()); - quat.projectOnAxis(axis); - rotation = Quaternion(quat, 2.0*acos(rotation[3])); - break; - } - case AxisPlaneConstraint::FORBIDDEN: - rotation = Quaternion(); // identity - break; - } + switch (rotationConstraintType()) + { + case AxisPlaneConstraint::FREE: + break; + case AxisPlaneConstraint::PLANE: + break; + case AxisPlaneConstraint::AXIS: + { + Vec quat(rotation[0], rotation[1], rotation[2]); + Vec axis = frame->transformOf(rotationConstraintDirection()); + quat.projectOnAxis(axis); + rotation = Quaternion(quat, 2.0*acos(rotation[3])); + break; + } + case AxisPlaneConstraint::FORBIDDEN: + rotation = Quaternion(); // identity + break; + } } //////////////////////////////////////////////////////////////////////////////// @@ -233,7 +234,7 @@ void WorldConstraint::constrainRotation(Quaternion& rotation, Frame* const frame /*! Creates a CameraConstraint, whose constrained directions are defined in the \p camera coordinate system. */ CameraConstraint::CameraConstraint(const Camera* const camera) - : AxisPlaneConstraint(), camera_(camera) + : AxisPlaneConstraint(), camera_(camera) {} /*! Depending on translationConstraintType(), constrain \p translation to be along an axis or @@ -241,27 +242,27 @@ CameraConstraint::CameraConstraint(const Camera* const camera) translationConstraintDirection(). */ void CameraConstraint::constrainTranslation(Vec& translation, Frame* const frame) { - Vec proj; - switch (translationConstraintType()) - { - case AxisPlaneConstraint::FREE: - break; - case AxisPlaneConstraint::PLANE: - proj = camera()->frame()->inverseTransformOf(translationConstraintDirection()); - if (frame->referenceFrame()) - proj = frame->referenceFrame()->transformOf(proj); - translation.projectOnPlane(proj); - break; - case AxisPlaneConstraint::AXIS: - proj = camera()->frame()->inverseTransformOf(translationConstraintDirection()); - if (frame->referenceFrame()) - proj = frame->referenceFrame()->transformOf(proj); - translation.projectOnAxis(proj); - break; - case AxisPlaneConstraint::FORBIDDEN: - translation = Vec(0.0, 0.0, 0.0); - break; - } + Vec proj; + switch (translationConstraintType()) + { + case AxisPlaneConstraint::FREE: + break; + case AxisPlaneConstraint::PLANE: + proj = camera()->frame()->inverseTransformOf(translationConstraintDirection()); + if (frame->referenceFrame()) + proj = frame->referenceFrame()->transformOf(proj); + translation.projectOnPlane(proj); + break; + case AxisPlaneConstraint::AXIS: + proj = camera()->frame()->inverseTransformOf(translationConstraintDirection()); + if (frame->referenceFrame()) + proj = frame->referenceFrame()->transformOf(proj); + translation.projectOnAxis(proj); + break; + case AxisPlaneConstraint::FORBIDDEN: + translation = Vec(0.0, 0.0, 0.0); + break; + } } /*! When rotationConstraintType() is AxisPlaneConstraint::AXIS, constrain \p rotation to be a rotation @@ -269,22 +270,22 @@ void CameraConstraint::constrainTranslation(Vec& translation, Frame* const frame rotationConstraintDirection(). */ void CameraConstraint::constrainRotation(Quaternion& rotation, Frame* const frame) { - switch (rotationConstraintType()) - { - case AxisPlaneConstraint::FREE: - break; - case AxisPlaneConstraint::PLANE: - break; - case AxisPlaneConstraint::AXIS: - { - Vec axis = frame->transformOf(camera()->frame()->inverseTransformOf(rotationConstraintDirection())); - Vec quat = Vec(rotation[0], rotation[1], rotation[2]); - quat.projectOnAxis(axis); - rotation = Quaternion(quat, 2.0*acos(rotation[3])); - } - break; - case AxisPlaneConstraint::FORBIDDEN: - rotation = Quaternion(); // identity - break; - } + switch (rotationConstraintType()) + { + case AxisPlaneConstraint::FREE: + break; + case AxisPlaneConstraint::PLANE: + break; + case AxisPlaneConstraint::AXIS: + { + Vec axis = frame->transformOf(camera()->frame()->inverseTransformOf(rotationConstraintDirection())); + Vec quat = Vec(rotation[0], rotation[1], rotation[2]); + quat.projectOnAxis(axis); + rotation = Quaternion(quat, 2.0*acos(rotation[3])); + } + break; + case AxisPlaneConstraint::FORBIDDEN: + rotation = Quaternion(); // identity + break; + } } diff --git a/octovis/src/extern/QGLViewer/constraint.h b/octovis/src/extern/QGLViewer/constraint.h index 3e7dd65f..d90d8203 100644 --- a/octovis/src/extern/QGLViewer/constraint.h +++ b/octovis/src/extern/QGLViewer/constraint.h @@ -1,8 +1,8 @@ /**************************************************************************** - Copyright (C) 2002-2013 Gilles Debunne. All rights reserved. + Copyright (C) 2002-2014 Gilles Debunne. All rights reserved. - This file is part of the QGLViewer library version 2.4.0. + This file is part of the QGLViewer library version 2.6.3. http://www.libqglviewer.com - contact@libqglviewer.com @@ -27,10 +27,10 @@ #include "quaternion.h" namespace qglviewer { - class Frame; - class Camera; +class Frame; +class Camera; - /*! \brief An interface class for Frame constraints. +/*! \brief An interface class for Frame constraints. \class Constraint constraint.h QGLViewer/constraint.h This class defines the interface for the Constraints that can be applied to a Frame to limit its @@ -47,16 +47,16 @@ namespace qglviewer { \code Frame::translate(Vec& T) { - if (constraint()) - constraint()->constrainTranslation(T, this); - t += T; + if (constraint()) + constraint()->constrainTranslation(T, this); + t += T; } Frame::rotate(Quaternion& Q) { - if (constraint()) - constraint()->constrainRotation(Q, this); - q *= Q; + if (constraint()) + constraint()->constrainRotation(Q, this); + q *= Q; } \endcode @@ -88,13 +88,13 @@ namespace qglviewer { class myConstraint : public Constraint { public: - virtual void constrainTranslation(Vec& t, Frame * const fr) - { - // Express t in the world coordinate system. - const Vec tWorld = fr->inverseTransformOf(t); + virtual void constrainTranslation(Vec& t, Frame * const fr) + { + // Express t in the world coordinate system. + const Vec tWorld = fr->inverseTransformOf(t); if (fr->position().z + tWorld.z < 0.0) // check the new fr z coordinate t.z = fr->transformOf(-fr->position().z); // t.z is clamped so that next z position is 0.0 - } + } }; \endcode @@ -108,41 +108,41 @@ namespace qglviewer { \code myConstraint::constrainTranslation(Vec& v, Frame* const fr) { - constraint1->constrainTranslation(v, fr); - constraint2->constrainTranslation(v, fr); - // and so on, with possible branches, tests, loops... + constraint1->constrainTranslation(v, fr); + constraint2->constrainTranslation(v, fr); + // and so on, with possible branches, tests, loops... } \endcode */ - class QGLVIEWER_EXPORT Constraint - { - public: - /*! Virtual destructor. Empty. */ - virtual ~Constraint() {}; - - /*! Filters the translation applied to the \p frame. This default implementation is empty (no - filtering). - - Overload this method in your own Constraint class to define a new translation constraint. \p - frame is the Frame to which is applied the translation. It is not defined \c const, but you - should refrain from directly changing its value in the constraint. Use its Frame::position() and - update the \p translation accordingly instead. - - \p translation is expressed in local frame coordinate system. Use Frame::inverseTransformOf() to - express it in the world coordinate system if needed. */ - virtual void constrainTranslation(Vec& translation, Frame* const frame) { Q_UNUSED(translation); Q_UNUSED(frame); }; - /*! Filters the rotation applied to the \p frame. This default implementation is empty (no - filtering). - - Overload this method in your own Constraint class to define a new rotation constraint. See - constrainTranslation() for details. - - Use Frame::inverseTransformOf() on the \p rotation Quaternion::axis() to express \p rotation in - the world coordinate system if needed. */ - virtual void constrainRotation(Quaternion& rotation, Frame* const frame) { Q_UNUSED(rotation); Q_UNUSED(frame); }; - }; - - /*! +class QGLVIEWER_EXPORT Constraint +{ +public: + /*! Virtual destructor. Empty. */ + virtual ~Constraint() {} + + /*! Filters the translation applied to the \p frame. This default implementation is empty (no + filtering). + + Overload this method in your own Constraint class to define a new translation constraint. \p + frame is the Frame to which is applied the translation. It is not defined \c const, but you + should refrain from directly changing its value in the constraint. Use its Frame::position() and + update the \p translation accordingly instead. + + \p translation is expressed in local frame coordinate system. Use Frame::inverseTransformOf() to + express it in the world coordinate system if needed. */ + virtual void constrainTranslation(Vec& translation, Frame* const frame) { Q_UNUSED(translation); Q_UNUSED(frame); } + /*! Filters the rotation applied to the \p frame. This default implementation is empty (no + filtering). + + Overload this method in your own Constraint class to define a new rotation constraint. See + constrainTranslation() for details. + + Use Frame::inverseTransformOf() on the \p rotation Quaternion::axis() to express \p rotation in + the world coordinate system if needed. */ + virtual void constrainRotation(Quaternion& rotation, Frame* const frame) { Q_UNUSED(rotation); Q_UNUSED(frame); } +}; + +/*! \brief An abstract class for Frame Constraints defined by an axis or a plane. \class AxisPlaneConstraint constraint.h QGLViewer/constraint.h @@ -165,150 +165,150 @@ namespace qglviewer { However, adding an extra pointer to the QGLViewer::camera() in all the AxisPlaneConstraint derived classes (which the user would have to update in a multi-viewer application) was judged as an overkill. */ - class QGLVIEWER_EXPORT AxisPlaneConstraint : public Constraint - { - public: - AxisPlaneConstraint(); - /*! Virtual destructor. Empty. */ - virtual ~AxisPlaneConstraint() {}; - - /*! Type lists the different types of translation and rotation constraints that are available. - - It specifies the meaning of the constraint direction (see translationConstraintDirection() and - rotationConstraintDirection()): as an axis direction (AxisPlaneConstraint::AXIS) or a plane - normal (AxisPlaneConstraint::PLANE). AxisPlaneConstraint::FREE means no constraint while - AxisPlaneConstraint::FORBIDDEN completely forbids the translation and/or the rotation. - - See translationConstraintType() and rotationConstraintType(). - - \attention The AxisPlaneConstraint::PLANE Type is not valid for rotational constraint. - - New derived classes can use their own extended enum for specific constraints: - \code - class MyAxisPlaneConstraint : public AxisPlaneConstraint - { - public: - enum MyType { FREE, AXIS, PLANE, FORBIDDEN, CUSTOM }; - virtual void constrainTranslation(Vec &translation, Frame *const frame) - { - // translationConstraintType() is simply an int. CUSTOM Type is handled seamlessly. - switch (translationConstraintType()) - { - case MyAxisPlaneConstraint::FREE: ... break; - case MyAxisPlaneConstraint::CUSTOM: ... break; - } - }; - - MyAxisPlaneConstraint* c = new MyAxisPlaneConstraint(); - // Note the Type conversion - c->setTranslationConstraintType(AxisPlaneConstraint::Type(MyAxisPlaneConstraint::CUSTOM)); - }; - \endcode */ - enum Type { FREE, AXIS, PLANE, FORBIDDEN }; - - /*! @name Translation constraint */ - //@{ - /*! Overloading of Constraint::constrainTranslation(). Empty */ - virtual void constrainTranslation(Vec& translation, Frame* const frame) { Q_UNUSED(translation); Q_UNUSED(frame); }; - - void setTranslationConstraint(Type type, const Vec& direction); - /*! Sets the Type() of the translationConstraintType(). Default is AxisPlaneConstraint::FREE. */ - void setTranslationConstraintType(Type type) { translationConstraintType_ = type; }; - void setTranslationConstraintDirection(const Vec& direction); - - /*! Returns the translation constraint Type(). - - Depending on this value, the Frame will freely translate (AxisPlaneConstraint::FREE), will only - be able to translate along an axis direction (AxisPlaneConstraint::AXIS), will be forced to stay - into a plane (AxisPlaneConstraint::PLANE) or will not able to translate at all - (AxisPlaneConstraint::FORBIDDEN). - - Use Frame::setPosition() to define the position of the constrained Frame before it gets - constrained. */ - Type translationConstraintType() const { return translationConstraintType_; }; - /*! Returns the direction used by the translation constraint. - - It represents the axis direction (AxisPlaneConstraint::AXIS) or the plane normal - (AxisPlaneConstraint::PLANE) depending on the translationConstraintType(). It is undefined for - AxisPlaneConstraint::FREE or AxisPlaneConstraint::FORBIDDEN. - - The AxisPlaneConstraint derived classes express this direction in different coordinate system - (camera for CameraConstraint, local for LocalConstraint, and world for WorldConstraint). This - value can be modified with setTranslationConstraintDirection(). */ - Vec translationConstraintDirection() const { return translationConstraintDir_; }; - //@} - - /*! @name Rotation constraint */ - //@{ - /*! Overloading of Constraint::constrainRotation(). Empty. */ - virtual void constrainRotation(Quaternion& rotation, Frame* const frame) { Q_UNUSED(rotation); Q_UNUSED(frame); }; - - void setRotationConstraint(Type type, const Vec& direction); - void setRotationConstraintType(Type type); - void setRotationConstraintDirection(const Vec& direction); - - /*! Returns the rotation constraint Type(). */ - Type rotationConstraintType() const { return rotationConstraintType_; }; - /*! Returns the axis direction used by the rotation constraint. - - This direction is defined only when rotationConstraintType() is AxisPlaneConstraint::AXIS. - - The AxisPlaneConstraint derived classes express this direction in different coordinate system - (camera for CameraConstraint, local for LocalConstraint, and world for WorldConstraint). This - value can be modified with setRotationConstraintDirection(). */ - Vec rotationConstraintDirection() const { return rotationConstraintDir_; }; - //@} - - private: - // int and not Type to allow for overloading and new types definition. - Type translationConstraintType_; - Type rotationConstraintType_; - - Vec translationConstraintDir_; - Vec rotationConstraintDir_; - }; +class QGLVIEWER_EXPORT AxisPlaneConstraint : public Constraint +{ +public: + AxisPlaneConstraint(); + /*! Virtual destructor. Empty. */ + virtual ~AxisPlaneConstraint() {} + + /*! Type lists the different types of translation and rotation constraints that are available. + + It specifies the meaning of the constraint direction (see translationConstraintDirection() and + rotationConstraintDirection()): as an axis direction (AxisPlaneConstraint::AXIS) or a plane + normal (AxisPlaneConstraint::PLANE). AxisPlaneConstraint::FREE means no constraint while + AxisPlaneConstraint::FORBIDDEN completely forbids the translation and/or the rotation. + See translationConstraintType() and rotationConstraintType(). - /*! \brief An AxisPlaneConstraint defined in the Frame local coordinate system. + \attention The AxisPlaneConstraint::PLANE Type is not valid for rotational constraint. + + New derived classes can use their own extended enum for specific constraints: + \code + class MyAxisPlaneConstraint : public AxisPlaneConstraint + { + public: + enum MyType { FREE, AXIS, PLANE, FORBIDDEN, CUSTOM }; + virtual void constrainTranslation(Vec &translation, Frame *const frame) + { + // translationConstraintType() is simply an int. CUSTOM Type is handled seamlessly. + switch (translationConstraintType()) + { + case MyAxisPlaneConstraint::FREE: ... break; + case MyAxisPlaneConstraint::CUSTOM: ... break; + } + }; + + MyAxisPlaneConstraint* c = new MyAxisPlaneConstraint(); + // Note the Type conversion + c->setTranslationConstraintType(AxisPlaneConstraint::Type(MyAxisPlaneConstraint::CUSTOM)); + }; + \endcode */ + enum Type { FREE, AXIS, PLANE, FORBIDDEN }; + + /*! @name Translation constraint */ + //@{ + /*! Overloading of Constraint::constrainTranslation(). Empty */ + virtual void constrainTranslation(Vec& translation, Frame* const frame) { Q_UNUSED(translation); Q_UNUSED(frame); }; + + void setTranslationConstraint(Type type, const Vec& direction); + /*! Sets the Type() of the translationConstraintType(). Default is AxisPlaneConstraint::FREE. */ + void setTranslationConstraintType(Type type) { translationConstraintType_ = type; }; + void setTranslationConstraintDirection(const Vec& direction); + + /*! Returns the translation constraint Type(). + + Depending on this value, the Frame will freely translate (AxisPlaneConstraint::FREE), will only + be able to translate along an axis direction (AxisPlaneConstraint::AXIS), will be forced to stay + into a plane (AxisPlaneConstraint::PLANE) or will not able to translate at all + (AxisPlaneConstraint::FORBIDDEN). + + Use Frame::setPosition() to define the position of the constrained Frame before it gets + constrained. */ + Type translationConstraintType() const { return translationConstraintType_; }; + /*! Returns the direction used by the translation constraint. + + It represents the axis direction (AxisPlaneConstraint::AXIS) or the plane normal + (AxisPlaneConstraint::PLANE) depending on the translationConstraintType(). It is undefined for + AxisPlaneConstraint::FREE or AxisPlaneConstraint::FORBIDDEN. + + The AxisPlaneConstraint derived classes express this direction in different coordinate system + (camera for CameraConstraint, local for LocalConstraint, and world for WorldConstraint). This + value can be modified with setTranslationConstraintDirection(). */ + Vec translationConstraintDirection() const { return translationConstraintDir_; }; + //@} + + /*! @name Rotation constraint */ + //@{ + /*! Overloading of Constraint::constrainRotation(). Empty. */ + virtual void constrainRotation(Quaternion& rotation, Frame* const frame) { Q_UNUSED(rotation); Q_UNUSED(frame); }; + + void setRotationConstraint(Type type, const Vec& direction); + void setRotationConstraintType(Type type); + void setRotationConstraintDirection(const Vec& direction); + + /*! Returns the rotation constraint Type(). */ + Type rotationConstraintType() const { return rotationConstraintType_; }; + /*! Returns the axis direction used by the rotation constraint. + + This direction is defined only when rotationConstraintType() is AxisPlaneConstraint::AXIS. + + The AxisPlaneConstraint derived classes express this direction in different coordinate system + (camera for CameraConstraint, local for LocalConstraint, and world for WorldConstraint). This + value can be modified with setRotationConstraintDirection(). */ + Vec rotationConstraintDirection() const { return rotationConstraintDir_; }; + //@} + +private: + // int and not Type to allow for overloading and new types definition. + Type translationConstraintType_; + Type rotationConstraintType_; + + Vec translationConstraintDir_; + Vec rotationConstraintDir_; +}; + + +/*! \brief An AxisPlaneConstraint defined in the Frame local coordinate system. \class LocalConstraint constraint.h QGLViewer/constraint.h The translationConstraintDirection() and rotationConstraintDirection() are expressed in the Frame local coordinate system (see Frame::referenceFrame()). See the constrainedFrame example for an illustration. */ - class QGLVIEWER_EXPORT LocalConstraint : public AxisPlaneConstraint - { - public: - /*! Virtual destructor. Empty. */ - virtual ~LocalConstraint() {}; +class QGLVIEWER_EXPORT LocalConstraint : public AxisPlaneConstraint +{ +public: + /*! Virtual destructor. Empty. */ + virtual ~LocalConstraint() {}; - virtual void constrainTranslation(Vec& translation, Frame* const frame); - virtual void constrainRotation (Quaternion& rotation, Frame* const frame); - }; + virtual void constrainTranslation(Vec& translation, Frame* const frame); + virtual void constrainRotation (Quaternion& rotation, Frame* const frame); +}; - /*! \brief An AxisPlaneConstraint defined in the world coordinate system. - \class WorldConstraint constraint.h QGLViewer/constraint.h +/*! \brief An AxisPlaneConstraint defined in the world coordinate system. + \class WorldConstraint constraint.h QGLViewer/constraint.h The translationConstraintDirection() and rotationConstraintDirection() are expressed in world coordinate system. See the constrainedFrame and multiView examples for an illustration. */ - class QGLVIEWER_EXPORT WorldConstraint : public AxisPlaneConstraint - { - public: - /*! Virtual destructor. Empty. */ - virtual ~WorldConstraint() {}; +class QGLVIEWER_EXPORT WorldConstraint : public AxisPlaneConstraint +{ +public: + /*! Virtual destructor. Empty. */ + virtual ~WorldConstraint() {}; - virtual void constrainTranslation(Vec& translation, Frame* const frame); - virtual void constrainRotation (Quaternion& rotation, Frame* const frame); - }; + virtual void constrainTranslation(Vec& translation, Frame* const frame); + virtual void constrainRotation (Quaternion& rotation, Frame* const frame); +}; - /*! \brief An AxisPlaneConstraint defined in the camera coordinate system. +/*! \brief An AxisPlaneConstraint defined in the camera coordinate system. \class CameraConstraint constraint.h QGLViewer/constraint.h The translationConstraintDirection() and rotationConstraintDirection() are expressed in the @@ -316,22 +316,22 @@ namespace qglviewer { See the constrainedFrame and constrainedCamera examples for an illustration. */ - class QGLVIEWER_EXPORT CameraConstraint : public AxisPlaneConstraint - { - public: - explicit CameraConstraint(const Camera* const camera); - /*! Virtual destructor. Empty. */ - virtual ~CameraConstraint() {}; - - virtual void constrainTranslation(Vec& translation, Frame* const frame); - virtual void constrainRotation (Quaternion& rotation, Frame* const frame); - - /*! Returns the associated Camera. Set using the CameraConstraint constructor. */ - const Camera* camera() const { return camera_; }; - - private: - const Camera* const camera_; - }; +class QGLVIEWER_EXPORT CameraConstraint : public AxisPlaneConstraint +{ +public: + explicit CameraConstraint(const Camera* const camera); + /*! Virtual destructor. Empty. */ + virtual ~CameraConstraint() {}; + + virtual void constrainTranslation(Vec& translation, Frame* const frame); + virtual void constrainRotation (Quaternion& rotation, Frame* const frame); + + /*! Returns the associated Camera. Set using the CameraConstraint constructor. */ + const Camera* camera() const { return camera_; }; + +private: + const Camera* const camera_; +}; } // namespace qglviewer diff --git a/octovis/src/extern/QGLViewer/domUtils.h b/octovis/src/extern/QGLViewer/domUtils.h index f6e9edf4..39944683 100644 --- a/octovis/src/extern/QGLViewer/domUtils.h +++ b/octovis/src/extern/QGLViewer/domUtils.h @@ -1,8 +1,8 @@ /**************************************************************************** - Copyright (C) 2002-2013 Gilles Debunne. All rights reserved. + Copyright (C) 2002-2014 Gilles Debunne. All rights reserved. - This file is part of the QGLViewer library version 2.4.0. + This file is part of the QGLViewer library version 2.6.3. http://www.libqglviewer.com - contact@libqglviewer.com @@ -22,18 +22,10 @@ #include "config.h" -#if QT_VERSION >= 0x040000 -# include -# include -# include -# include -#else -# include -# include -# include -# include -# include -#endif +#include +#include +#include +#include #include @@ -43,133 +35,127 @@ class DomUtils { private: - static void warning(const QString& message) - { -#if QT_VERSION >= 0x040000 - qWarning("%s", message.toLatin1().constData()); -#else - qWarning("%s", message.latin1()); -#endif - } + static void warning(const QString& message) + { + qWarning("%s", message.toLatin1().constData()); + } public: - static float floatFromDom(const QDomElement& e, const QString& attribute, float defValue) - { - float value = defValue; - if (e.hasAttribute(attribute)) { - const QString s = e.attribute(attribute); - bool ok; - value = s.toFloat(&ok); - if (!ok) { - warning("Bad float syntax for attribute \""+attribute+"\" in initialization of \""+e.tagName()+"\". Setting value to "+QString::number(value)+"."); - value = defValue; - } - } else - warning("\""+attribute+"\" attribute missing in initialization of \""+e.tagName()+"\". Setting value to "+QString::number(value)+"."); + static qreal qrealFromDom(const QDomElement& e, const QString& attribute, qreal defValue) + { + qreal value = defValue; + if (e.hasAttribute(attribute)) { + const QString s = e.attribute(attribute); + bool ok; + value = s.toDouble(&ok); + if (!ok) { + warning(QString("'%1' is not a valid qreal syntax for attribute \"%2\" in initialization of \"%3\". Setting value to %4.") + .arg(s).arg(attribute).arg(e.tagName()).arg(QString::number(defValue))); + value = defValue; + } + } else { + warning(QString("\"%1\" attribute missing in initialization of \"%2\". Setting value to %3.") + .arg(attribute).arg(e.tagName()).arg(QString::number(value))); + } #if defined(isnan) - // The "isnan" method may not be available on all platforms. - // Find its equivalent or simply remove these two lines - if (isnan(value)) - warning("Warning, attribute \""+attribute+"\" initialized to Not a Number in \""+e.tagName()+"\""); + // The "isnan" method may not be available on all platforms. + // Find its equivalent or simply remove these two lines + if (isnan(value)) + warning(QString("Warning, attribute \"%1\" initialized to Not a Number in \"%2\"") + .arg(attribute).arg(e.tagName())); #endif - return value; - } - - static double doubleFromDom(const QDomElement& e, const QString& attribute, double defValue) - { - double value = defValue; - if (e.hasAttribute(attribute)) { - const QString s = e.attribute(attribute); - bool ok; - value = s.toDouble(&ok); - if (!ok) { - warning("Bad double syntax for attribute \""+attribute+"\" in initialization of \""+e.tagName()+"\". Setting value to "+QString::number(value)+"."); - value = defValue; - } - } else - warning("\""+attribute+"\" attribute missing in initialization of \""+e.tagName()+"\". Setting value to "+QString::number(value)+"."); - -#if defined(isnan) - // The "isnan" method may not be available on all platforms. - // Find its equivalent or simply remove these two lines - if (isnan(value)) - warning("Warning, attribute \""+attribute+"\" initialized to Not a Number in \""+e.tagName()+"\""); -#endif - - return value; - } - - static int intFromDom(const QDomElement& e, const QString& attribute, int defValue) - { - int value = defValue; - if (e.hasAttribute(attribute)) - { - const QString s = e.attribute(attribute); - bool ok; - s.toInt(&ok); - if (ok) - value = s.toInt(); - else - warning("Bad integer syntax for attribute \""+attribute+"\" in initialization of \""+e.tagName()+"\". Setting value to "+QString::number(value)+"."); - } - else - warning("\""+attribute+"\" attribute missing in initialization of \""+e.tagName()+"\". Setting value to "+QString::number(value)+"."); - return value; - } - - static bool boolFromDom(const QDomElement& e, const QString& attribute, bool defValue) - { - bool value = defValue; - if (e.hasAttribute(attribute)) - { - const QString s = e.attribute(attribute); -#if QT_VERSION >= 0x040000 - if (s.toLower() == QString("true")) -#else - if (s.lower() == QString("true")) -#endif - value = true; -#if QT_VERSION >= 0x040000 - else if (s.toLower() == QString("false")) -#else - else if (s.lower() == QString("false")) -#endif - value = false; - else - { - warning("Bad boolean syntax for attribute \""+attribute+"\" in initialization of \""+e.tagName()+"\" (should be \"true\" or \"false\")."); - warning("Setting value to "+(value?QString("true."):QString("false."))); - } - } - else - warning("\""+attribute+"\" attribute missing in initialization of \""+e.tagName()+"\". Setting value to "+(value?QString("true."):QString("false."))); - return value; - } - - static QDomElement QColorDomElement(const QColor& color, const QString& name, QDomDocument& doc) - { - QDomElement de = doc.createElement(name); - de.setAttribute("red", QString::number(color.red())); - de.setAttribute("green", QString::number(color.green())); - de.setAttribute("blue", QString::number(color.blue())); - return de; - } - - static QColor QColorFromDom(const QDomElement& e) - { - int color[3]; - QStringList attribute; - attribute << "red" << "green" << "blue"; -#if QT_VERSION >= 0x040000 - for (int i=0; imatrix()); - drawBody(); + glPushMatrix(); + glMultMatrixd(body->matrix()); + drawBody(); - glPushMatrix(); - glMultMatrixd(leftArm->matrix()); - drawArm(); - glPopMatrix(); + glPushMatrix(); + glMultMatrixd(leftArm->matrix()); + drawArm(); + glPopMatrix(); - glPushMatrix(); - glMultMatrixd(rightArm->matrix()); - drawArm(); - glPopMatrix(); + glPushMatrix(); + glMultMatrixd(rightArm->matrix()); + drawArm(); + glPopMatrix(); - glPopMatrix(); + glPopMatrix(); } \endcode Note the use of nested \c glPushMatrix() and \c glPopMatrix() blocks to represent the frame hierarchy: \c @@ -122,29 +122,29 @@ Frame::Frame(const Frame& frame) \note The scaling factor of the 4x4 matrix is 1.0. */ const GLdouble* Frame::matrix() const { - static GLdouble m[4][4]; - getMatrix(m); - return (const GLdouble*)(m); + static GLdouble m[4][4]; + getMatrix(m); + return (const GLdouble*)(m); } /*! \c GLdouble[4][4] version of matrix(). See also getWorldMatrix() and matrix(). */ void Frame::getMatrix(GLdouble m[4][4]) const { - q_.getMatrix(m); + q_.getMatrix(m); - m[3][0] = t_[0]; - m[3][1] = t_[1]; - m[3][2] = t_[2]; + m[3][0] = t_[0]; + m[3][1] = t_[1]; + m[3][2] = t_[2]; } /*! \c GLdouble[16] version of matrix(). See also getWorldMatrix() and matrix(). */ void Frame::getMatrix(GLdouble m[16]) const { - q_.getMatrix(m); + q_.getMatrix(m); - m[12] = t_[0]; - m[13] = t_[1]; - m[14] = t_[2]; + m[12] = t_[0]; + m[13] = t_[1]; + m[14] = t_[2]; } /*! Returns a Frame representing the inverse of the Frame space transformation. @@ -163,9 +163,9 @@ void Frame::getMatrix(GLdouble m[16]) const \note The scaling factor of the 4x4 matrix is 1.0. */ Frame Frame::inverse() const { - Frame fr(-(q_.inverseRotate(t_)), q_.inverse()); - fr.setReferenceFrame(referenceFrame()); - return fr; + Frame fr(-(q_.inverseRotate(t_)), q_.inverse()); + fr.setReferenceFrame(referenceFrame()); + return fr; } /*! Returns the 4x4 OpenGL transformation matrix represented by the Frame. @@ -195,54 +195,54 @@ Frame Frame::inverse() const \note The scaling factor of the 4x4 matrix is 1.0. */ const GLdouble* Frame::worldMatrix() const { - // This test is done for efficiency reasons (creates lots of temp objects otherwise). - if (referenceFrame()) - { - static Frame fr; - fr.setTranslation(position()); - fr.setRotation(orientation()); - return fr.matrix(); - } - else - return matrix(); + // This test is done for efficiency reasons (creates lots of temp objects otherwise). + if (referenceFrame()) + { + static Frame fr; + fr.setTranslation(position()); + fr.setRotation(orientation()); + return fr.matrix(); + } + else + return matrix(); } -/*! float[4][4] parameter version of worldMatrix(). See also getMatrix() and matrix(). */ +/*! qreal[4][4] parameter version of worldMatrix(). See also getMatrix() and matrix(). */ void Frame::getWorldMatrix(GLdouble m[4][4]) const { - const GLdouble* mat = worldMatrix(); - for (int i=0; i<4; ++i) - for (int j=0; j<4; ++j) - m[i][j] = mat[i*4+j]; + const GLdouble* mat = worldMatrix(); + for (int i=0; i<4; ++i) + for (int j=0; j<4; ++j) + m[i][j] = mat[i*4+j]; } -/*! float[16] parameter version of worldMatrix(). See also getMatrix() and matrix(). */ +/*! qreal[16] parameter version of worldMatrix(). See also getMatrix() and matrix(). */ void Frame::getWorldMatrix(GLdouble m[16]) const { - const GLdouble* mat = worldMatrix(); - for (int i=0; i<16; ++i) - m[i] = mat[i]; + const GLdouble* mat = worldMatrix(); + for (int i=0; i<16; ++i) + m[i] = mat[i]; } /*! This is an overloaded method provided for convenience. Same as setFromMatrix(). */ void Frame::setFromMatrix(const GLdouble m[4][4]) { - if (fabs(m[3][3]) < 1E-8) - { - qWarning("Frame::setFromMatrix: Null homogeneous coefficient"); - return; - } + if (fabs(m[3][3]) < 1E-8) + { + qWarning("Frame::setFromMatrix: Null homogeneous coefficient"); + return; + } - double rot[3][3]; - for (int i=0; i<3; ++i) - { - t_[i] = m[3][i] / m[3][3]; - for (int j=0; j<3; ++j) - // Beware of the transposition (OpenGL to European math) - rot[i][j] = m[j][i] / m[3][3]; - } - q_.setFromRotationMatrix(rot); - Q_EMIT modified(); + qreal rot[3][3]; + for (int i=0; i<3; ++i) + { + t_[i] = m[3][i] / m[3][3]; + for (int j=0; j<3; ++j) + // Beware of the transposition (OpenGL to European math) + rot[i][j] = m[j][i] / m[3][3]; + } + q_.setFromRotationMatrix(rot); + Q_EMIT modified(); } /*! Sets the Frame from an OpenGL matrix representation (rotation in the upper left 3x3 matrix and @@ -271,47 +271,47 @@ void Frame::setFromMatrix(const GLdouble m[4][4]) converted into the Frame by this method. */ void Frame::setFromMatrix(const GLdouble m[16]) { - GLdouble mat[4][4]; - for (int i=0; i<4; ++i) - for (int j=0; j<4; ++j) - mat[i][j] = m[i*4+j]; - setFromMatrix(mat); + GLdouble mat[4][4]; + for (int i=0; i<4; ++i) + for (int j=0; j<4; ++j) + mat[i][j] = m[i*4+j]; + setFromMatrix(mat); } //////////////////// SET AND GET LOCAL TRANSLATION AND ROTATION /////////////////////////////// -/*! Same as setTranslation(), but with \p float parameters. */ -void Frame::setTranslation(float x, float y, float z) +/*! Same as setTranslation(), but with \p qreal parameters. */ +void Frame::setTranslation(qreal x, qreal y, qreal z) { - setTranslation(Vec(x, y, z)); + setTranslation(Vec(x, y, z)); } /*! Fill \c x, \c y and \c z with the translation() of the Frame. */ -void Frame::getTranslation(float& x, float& y, float& z) const +void Frame::getTranslation(qreal& x, qreal& y, qreal& z) const { - const Vec t = translation(); - x = t[0]; - y = t[1]; - z = t[2]; + const Vec t = translation(); + x = t[0]; + y = t[1]; + z = t[2]; } -/*! Same as setRotation() but with \c float Quaternion parameters. */ -void Frame::setRotation(double q0, double q1, double q2, double q3) +/*! Same as setRotation() but with \c qreal Quaternion parameters. */ +void Frame::setRotation(qreal q0, qreal q1, qreal q2, qreal q3) { - setRotation(Quaternion(q0, q1, q2, q3)); + setRotation(Quaternion(q0, q1, q2, q3)); } /*! The \p q are set to the rotation() of the Frame. -See Quaternion::Quaternion(double, double, double, double) for details on \c q. */ -void Frame::getRotation(double& q0, double& q1, double& q2, double& q3) const +See Quaternion::Quaternion(qreal, qreal, qreal, qreal) for details on \c q. */ +void Frame::getRotation(qreal& q0, qreal& q1, qreal& q2, qreal& q3) const { - const Quaternion q = rotation(); - q0 = q[0]; - q1 = q[1]; - q2 = q[2]; - q3 = q[3]; + const Quaternion q = rotation(); + q0 = q[0]; + q1 = q[1]; + q2 = q[2]; + q3 = q[3]; } //////////////////////////////////////////////////////////////////////////////// @@ -326,35 +326,35 @@ void Frame::getRotation(double& q0, double& q1, double& q2, double& q3) const See also rotate(const Quaternion&). Emits the modified() signal. */ void Frame::translate(const Vec& t) { - Vec tbis = t; - translate(tbis); + Vec tbis = t; + translate(tbis); } /*! Same as translate(const Vec&) but \p t may be modified to satisfy the translation constraint(). Its new value corresponds to the translation that has actually been applied to the Frame. */ void Frame::translate(Vec& t) { - if (constraint()) - constraint()->constrainTranslation(t, this); - t_ += t; - Q_EMIT modified(); + if (constraint()) + constraint()->constrainTranslation(t, this); + t_ += t; + Q_EMIT modified(); } -/*! Same as translate(const Vec&) but with \c float parameters. */ -void Frame::translate(float x, float y, float z) +/*! Same as translate(const Vec&) but with \c qreal parameters. */ +void Frame::translate(qreal x, qreal y, qreal z) { - Vec t(x,y,z); - translate(t); + Vec t(x,y,z); + translate(t); } -/*! Same as translate(Vec&) but with \c float parameters. */ -void Frame::translate(float& x, float& y, float& z) +/*! Same as translate(Vec&) but with \c qreal parameters. */ +void Frame::translate(qreal& x, qreal& y, qreal& z) { - Vec t(x,y,z); - translate(t); - x = t[0]; - y = t[1]; - z = t[2]; + Vec t(x,y,z); + translate(t); + x = t[0]; + y = t[1]; + z = t[2]; } /*! Rotates the Frame by \p q (defined in the Frame coordinate system): R = R*q. @@ -367,37 +367,37 @@ void Frame::translate(float& x, float& y, float& z) See also translate(const Vec&). Emits the modified() signal. */ void Frame::rotate(const Quaternion& q) { - Quaternion qbis = q; - rotate(qbis); + Quaternion qbis = q; + rotate(qbis); } /*! Same as rotate(const Quaternion&) but \p q may be modified to satisfy the rotation constraint(). Its new value corresponds to the rotation that has actually been applied to the Frame. */ void Frame::rotate(Quaternion& q) { - if (constraint()) - constraint()->constrainRotation(q, this); - q_ *= q; - q_.normalize(); // Prevents numerical drift - Q_EMIT modified(); + if (constraint()) + constraint()->constrainRotation(q, this); + q_ *= q; + q_.normalize(); // Prevents numerical drift + Q_EMIT modified(); } -/*! Same as rotate(Quaternion&) but with \c float Quaternion parameters. */ -void Frame::rotate(double& q0, double& q1, double& q2, double& q3) +/*! Same as rotate(Quaternion&) but with \c qreal Quaternion parameters. */ +void Frame::rotate(qreal& q0, qreal& q1, qreal& q2, qreal& q3) { - Quaternion q(q0,q1,q2,q3); - rotate(q); - q0 = q[0]; - q1 = q[1]; - q2 = q[2]; - q3 = q[3]; + Quaternion q(q0,q1,q2,q3); + rotate(q); + q0 = q[0]; + q1 = q[1]; + q2 = q[2]; + q3 = q[3]; } -/*! Same as rotate(const Quaternion&) but with \c float Quaternion parameters. */ -void Frame::rotate(double q0, double q1, double q2, double q3) +/*! Same as rotate(const Quaternion&) but with \c qreal Quaternion parameters. */ +void Frame::rotate(qreal q0, qreal q1, qreal q2, qreal q3) { - Quaternion q(q0,q1,q2,q3); - rotate(q); + Quaternion q(q0,q1,q2,q3); + rotate(q); } /*! Makes the Frame rotate() by \p rotation around \p point. @@ -413,23 +413,23 @@ void Frame::rotate(double q0, double q1, double q2, double q3) Emits the modified() signal. */ void Frame::rotateAroundPoint(Quaternion& rotation, const Vec& point) { - if (constraint()) - constraint()->constrainRotation(rotation, this); - q_ *= rotation; - q_.normalize(); // Prevents numerical drift - Vec trans = point + Quaternion(inverseTransformOf(rotation.axis()), rotation.angle()).rotate(position()-point) - t_; - if (constraint()) - constraint()->constrainTranslation(trans, this); - t_ += trans; - Q_EMIT modified(); + if (constraint()) + constraint()->constrainRotation(rotation, this); + q_ *= rotation; + q_.normalize(); // Prevents numerical drift + Vec trans = point + Quaternion(inverseTransformOf(rotation.axis()), rotation.angle()).rotate(position()-point) - t_; + if (constraint()) + constraint()->constrainTranslation(trans, this); + t_ += trans; + Q_EMIT modified(); } /*! Same as rotateAroundPoint(), but with a \c const \p rotation Quaternion. Note that the actual rotation may differ since it can be filtered by the constraint(). */ void Frame::rotateAroundPoint(const Quaternion& rotation, const Vec& point) { - Quaternion rot = rotation; - rotateAroundPoint(rot, point); + Quaternion rot = rotation; + rotateAroundPoint(rot, point); } //////////////////// SET AND GET WORLD POSITION AND ORIENTATION /////////////////////////////// @@ -442,59 +442,59 @@ referenceFrame()). The potential constraint() of the Frame is not taken into acc setPositionWithConstraint() instead. */ void Frame::setPosition(const Vec& position) { - if (referenceFrame()) - setTranslation(referenceFrame()->coordinatesOf(position)); - else - setTranslation(position); + if (referenceFrame()) + setTranslation(referenceFrame()->coordinatesOf(position)); + else + setTranslation(position); } -/*! Same as setPosition(), but with \c float parameters. */ -void Frame::setPosition(float x, float y, float z) +/*! Same as setPosition(), but with \c qreal parameters. */ +void Frame::setPosition(qreal x, qreal y, qreal z) { - setPosition(Vec(x, y, z)); + setPosition(Vec(x, y, z)); } /*! Same as successive calls to setPosition() and then setOrientation(). Only one modified() signal is emitted, which is convenient if this signal is connected to a -QGLViewer::updateGL() slot. See also setTranslationAndRotation() and +QGLViewer::update() slot. See also setTranslationAndRotation() and setPositionAndOrientationWithConstraint(). */ void Frame::setPositionAndOrientation(const Vec& position, const Quaternion& orientation) { - if (referenceFrame()) - { - t_ = referenceFrame()->coordinatesOf(position); - q_ = referenceFrame()->orientation().inverse() * orientation; - } - else - { - t_ = position; - q_ = orientation; - } - Q_EMIT modified(); + if (referenceFrame()) + { + t_ = referenceFrame()->coordinatesOf(position); + q_ = referenceFrame()->orientation().inverse() * orientation; + } + else + { + t_ = position; + q_ = orientation; + } + Q_EMIT modified(); } /*! Same as successive calls to setTranslation() and then setRotation(). Only one modified() signal is emitted, which is convenient if this signal is connected to a -QGLViewer::updateGL() slot. See also setPositionAndOrientation() and +QGLViewer::update() slot. See also setPositionAndOrientation() and setTranslationAndRotationWithConstraint(). */ void Frame::setTranslationAndRotation(const Vec& translation, const Quaternion& rotation) { - t_ = translation; - q_ = rotation; - Q_EMIT modified(); + t_ = translation; + q_ = rotation; + Q_EMIT modified(); } /*! \p x, \p y and \p z are set to the position() of the Frame. */ -void Frame::getPosition(float& x, float& y, float& z) const +void Frame::getPosition(qreal& x, qreal& y, qreal& z) const { - Vec p = position(); - x = p.x; - y = p.y; - z = p.z; + Vec p = position(); + x = p.x; + y = p.y; + z = p.z; } /*! Sets the orientation() of the Frame, defined in the world coordinate system. Emits the modified() signal. @@ -504,16 +504,16 @@ potential constraint() of the Frame is not taken into account, use setOrientatio instead. */ void Frame::setOrientation(const Quaternion& orientation) { - if (referenceFrame()) - setRotation(referenceFrame()->orientation().inverse() * orientation); - else - setRotation(orientation); + if (referenceFrame()) + setRotation(referenceFrame()->orientation().inverse() * orientation); + else + setRotation(orientation); } -/*! Same as setOrientation(), but with \c float parameters. */ -void Frame::setOrientation(double q0, double q1, double q2, double q3) +/*! Same as setOrientation(), but with \c qreal parameters. */ +void Frame::setOrientation(qreal q0, qreal q1, qreal q2, qreal q3) { - setOrientation(Quaternion(q0, q1, q2, q3)); + setOrientation(Quaternion(q0, q1, q2, q3)); } /*! Get the current orientation of the frame (same as orientation()). @@ -522,28 +522,37 @@ void Frame::setOrientation(double q0, double q1, double q2, double q3) /*! The \p q are set to the orientation() of the Frame. -See Quaternion::Quaternion(double, double, double, double) for details on \c q. */ -void Frame::getOrientation(double& q0, double& q1, double& q2, double& q3) const +See Quaternion::Quaternion(qreal, qreal, qreal, qreal) for details on \c q. */ +void Frame::getOrientation(qreal& q0, qreal& q1, qreal& q2, qreal& q3) const { - Quaternion o = orientation(); - q0 = o[0]; - q1 = o[1]; - q2 = o[2]; - q3 = o[3]; + Quaternion o = orientation(); + q0 = o[0]; + q1 = o[1]; + q2 = o[2]; + q3 = o[3]; +} + +/*! Returns the position of the Frame, defined in the world coordinate system. See also + orientation(), setPosition() and translation(). */ +Vec Frame::position() const { + if (referenceFrame_) + return inverseCoordinatesOf(Vec(0.0,0.0,0.0)); + else + return t_; } /*! Returns the orientation of the Frame, defined in the world coordinate system. See also position(), setOrientation() and rotation(). */ Quaternion Frame::orientation() const { - Quaternion res = rotation(); - const Frame* fr = referenceFrame(); - while (fr != NULL) - { - res = fr->rotation() * res; - fr = fr->referenceFrame(); - } - return res; + Quaternion res = rotation(); + const Frame* fr = referenceFrame(); + while (fr != NULL) + { + res = fr->rotation() * res; + fr = fr->referenceFrame(); + } + return res; } @@ -555,12 +564,12 @@ Quaternion Frame::orientation() const Emits the modified() signal. See also setRotationWithConstraint() and setPositionWithConstraint(). */ void Frame::setTranslationWithConstraint(Vec& translation) { - Vec deltaT = translation - this->translation(); - if (constraint()) - constraint()->constrainTranslation(deltaT, this); + Vec deltaT = translation - this->translation(); + if (constraint()) + constraint()->constrainTranslation(deltaT, this); - setTranslation(this->translation() + deltaT); - translation = this->translation(); + setTranslation(this->translation() + deltaT); + translation = this->translation(); } /*! Same as setRotation(), but \p rotation is modified so that the potential constraint() of the @@ -569,74 +578,74 @@ void Frame::setTranslationWithConstraint(Vec& translation) Emits the modified() signal. See also setTranslationWithConstraint() and setOrientationWithConstraint(). */ void Frame::setRotationWithConstraint(Quaternion& rotation) { - Quaternion deltaQ = this->rotation().inverse() * rotation; - if (constraint()) - constraint()->constrainRotation(deltaQ, this); + Quaternion deltaQ = this->rotation().inverse() * rotation; + if (constraint()) + constraint()->constrainRotation(deltaQ, this); - // Prevent numerical drift - deltaQ.normalize(); + // Prevent numerical drift + deltaQ.normalize(); - setRotation(this->rotation() * deltaQ); - q_.normalize(); - rotation = this->rotation(); + setRotation(this->rotation() * deltaQ); + q_.normalize(); + rotation = this->rotation(); } /*! Same as setTranslationAndRotation(), but \p translation and \p orientation are modified to satisfy the constraint(). Emits the modified() signal. */ void Frame::setTranslationAndRotationWithConstraint(Vec& translation, Quaternion& rotation) { - Vec deltaT = translation - this->translation(); - Quaternion deltaQ = this->rotation().inverse() * rotation; + Vec deltaT = translation - this->translation(); + Quaternion deltaQ = this->rotation().inverse() * rotation; - if (constraint()) - { - constraint()->constrainTranslation(deltaT, this); - constraint()->constrainRotation(deltaQ, this); - } + if (constraint()) + { + constraint()->constrainTranslation(deltaT, this); + constraint()->constrainRotation(deltaQ, this); + } - // Prevent numerical drift - deltaQ.normalize(); + // Prevent numerical drift + deltaQ.normalize(); - t_ += deltaT; - q_ *= deltaQ; - q_.normalize(); + t_ += deltaT; + q_ *= deltaQ; + q_.normalize(); - translation = this->translation(); - rotation = this->rotation(); + translation = this->translation(); + rotation = this->rotation(); - Q_EMIT modified(); + Q_EMIT modified(); } /*! Same as setPosition(), but \p position is modified so that the potential constraint() of the Frame is satisfied. See also setOrientationWithConstraint() and setTranslationWithConstraint(). */ void Frame::setPositionWithConstraint(Vec& position) { - if (referenceFrame()) - position = referenceFrame()->coordinatesOf(position); + if (referenceFrame()) + position = referenceFrame()->coordinatesOf(position); - setTranslationWithConstraint(position); + setTranslationWithConstraint(position); } /*! Same as setOrientation(), but \p orientation is modified so that the potential constraint() of the Frame is satisfied. See also setPositionWithConstraint() and setRotationWithConstraint(). */ void Frame::setOrientationWithConstraint(Quaternion& orientation) { - if (referenceFrame()) - orientation = referenceFrame()->orientation().inverse() * orientation; + if (referenceFrame()) + orientation = referenceFrame()->orientation().inverse() * orientation; - setRotationWithConstraint(orientation); + setRotationWithConstraint(orientation); } /*! Same as setPositionAndOrientation() but \p position and \p orientation are modified to satisfy the constraint. Emits the modified() signal. */ void Frame::setPositionAndOrientationWithConstraint(Vec& position, Quaternion& orientation) { - if (referenceFrame()) - { - position = referenceFrame()->coordinatesOf(position); - orientation = referenceFrame()->orientation().inverse() * orientation; - } - setTranslationAndRotationWithConstraint(position, orientation); + if (referenceFrame()) + { + position = referenceFrame()->coordinatesOf(position); + orientation = referenceFrame()->orientation().inverse() * orientation; + } + setTranslationAndRotationWithConstraint(position, orientation); } @@ -655,29 +664,29 @@ action is performed if setting \p refFrame as the referenceFrame() would create hierarchy (see settingAsReferenceFrameWillCreateALoop()). */ void Frame::setReferenceFrame(const Frame* const refFrame) { - if (settingAsReferenceFrameWillCreateALoop(refFrame)) - qWarning("Frame::setReferenceFrame would create a loop in Frame hierarchy"); - else - { - bool identical = (referenceFrame_ == refFrame); - referenceFrame_ = refFrame; - if (!identical) - Q_EMIT modified(); - } + if (settingAsReferenceFrameWillCreateALoop(refFrame)) + qWarning("Frame::setReferenceFrame would create a loop in Frame hierarchy"); + else + { + bool identical = (referenceFrame_ == refFrame); + referenceFrame_ = refFrame; + if (!identical) + Q_EMIT modified(); + } } /*! Returns \c true if setting \p frame as the Frame's referenceFrame() would create a loop in the Frame hierarchy. */ bool Frame::settingAsReferenceFrameWillCreateALoop(const Frame* const frame) { - const Frame* f = frame; - while (f != NULL) - { - if (f == this) - return true; - f = f->referenceFrame(); - } - return false; + const Frame* f = frame; + while (f != NULL) + { + if (f == this) + return true; + f = f->referenceFrame(); + } + return false; } ///////////////////////// FRAME TRANSFORMATIONS OF 3D POINTS ////////////////////////////// @@ -692,10 +701,10 @@ bool Frame::settingAsReferenceFrameWillCreateALoop(const Frame* const frame) illustration. */ Vec Frame::coordinatesOf(const Vec& src) const { - if (referenceFrame()) - return localCoordinatesOf(referenceFrame()->coordinatesOf(src)); - else - return localCoordinatesOf(src); + if (referenceFrame()) + return localCoordinatesOf(referenceFrame()->coordinatesOf(src)); + else + return localCoordinatesOf(src); } /*! Returns the world coordinates of the point whose position in the Frame coordinate system is \p @@ -705,14 +714,14 @@ Vec Frame::coordinatesOf(const Vec& src) const instead of 3D coordinates. */ Vec Frame::inverseCoordinatesOf(const Vec& src) const { - const Frame* fr = this; - Vec res = src; - while (fr != NULL) - { - res = fr->localInverseCoordinatesOf(res); - fr = fr->referenceFrame(); - } - return res; + const Frame* fr = this; + Vec res = src; + while (fr != NULL) + { + res = fr->localInverseCoordinatesOf(res); + fr = fr->referenceFrame(); + } + return res; } /*! Returns the Frame coordinates of a point \p src defined in the referenceFrame() coordinate @@ -721,7 +730,7 @@ Vec Frame::inverseCoordinatesOf(const Vec& src) const localInverseCoordinatesOf() performs the inverse convertion. See also localTransformOf(). */ Vec Frame::localCoordinatesOf(const Vec& src) const { - return rotation().inverseRotate(src - translation()); + return rotation().inverseRotate(src - translation()); } /*! Returns the referenceFrame() coordinates of a point \p src defined in the Frame coordinate @@ -730,7 +739,7 @@ Vec Frame::localCoordinatesOf(const Vec& src) const localCoordinatesOf() performs the inverse convertion. See also localInverseTransformOf(). */ Vec Frame::localInverseCoordinatesOf(const Vec& src) const { - return rotation().rotate(src) + translation(); + return rotation().rotate(src) + translation(); } /*! Returns the Frame coordinates of the point whose position in the \p from coordinate system is \p @@ -739,13 +748,13 @@ Vec Frame::localInverseCoordinatesOf(const Vec& src) const coordinatesOfIn() performs the inverse transformation. */ Vec Frame::coordinatesOfFrom(const Vec& src, const Frame* const from) const { - if (this == from) - return src; - else - if (referenceFrame()) - return localCoordinatesOf(referenceFrame()->coordinatesOfFrom(src, from)); - else - return localCoordinatesOf(from->inverseCoordinatesOf(src)); + if (this == from) + return src; + else + if (referenceFrame()) + return localCoordinatesOf(referenceFrame()->coordinatesOfFrom(src, from)); + else + return localCoordinatesOf(from->inverseCoordinatesOf(src)); } /*! Returns the \p in coordinates of the point whose position in the Frame coordinate system is \p @@ -754,70 +763,70 @@ Vec Frame::coordinatesOfFrom(const Vec& src, const Frame* const from) const coordinatesOfFrom() performs the inverse transformation. */ Vec Frame::coordinatesOfIn(const Vec& src, const Frame* const in) const { - const Frame* fr = this; - Vec res = src; - while ((fr != NULL) && (fr != in)) - { - res = fr->localInverseCoordinatesOf(res); - fr = fr->referenceFrame(); - } + const Frame* fr = this; + Vec res = src; + while ((fr != NULL) && (fr != in)) + { + res = fr->localInverseCoordinatesOf(res); + fr = fr->referenceFrame(); + } - if (fr != in) - // in was not found in the branch of this, res is now expressed in the world - // coordinate system. Simply convert to in coordinate system. - res = in->coordinatesOf(res); + if (fr != in) + // in was not found in the branch of this, res is now expressed in the world + // coordinate system. Simply convert to in coordinate system. + res = in->coordinatesOf(res); - return res; + return res; } -////// float[3] versions +////// qreal[3] versions -/*! Same as coordinatesOf(), but with \c float parameters. */ -void Frame::getCoordinatesOf(const float src[3], float res[3]) const +/*! Same as coordinatesOf(), but with \c qreal parameters. */ +void Frame::getCoordinatesOf(const qreal src[3], qreal res[3]) const { - const Vec r = coordinatesOf(Vec(src)); - for (int i=0; i<3 ; ++i) - res[i] = r[i]; + const Vec r = coordinatesOf(Vec(src)); + for (int i=0; i<3 ; ++i) + res[i] = r[i]; } -/*! Same as inverseCoordinatesOf(), but with \c float parameters. */ -void Frame::getInverseCoordinatesOf(const float src[3], float res[3]) const +/*! Same as inverseCoordinatesOf(), but with \c qreal parameters. */ +void Frame::getInverseCoordinatesOf(const qreal src[3], qreal res[3]) const { - const Vec r = inverseCoordinatesOf(Vec(src)); - for (int i=0; i<3 ; ++i) - res[i] = r[i]; + const Vec r = inverseCoordinatesOf(Vec(src)); + for (int i=0; i<3 ; ++i) + res[i] = r[i]; } -/*! Same as localCoordinatesOf(), but with \c float parameters. */ -void Frame::getLocalCoordinatesOf(const float src[3], float res[3]) const +/*! Same as localCoordinatesOf(), but with \c qreal parameters. */ +void Frame::getLocalCoordinatesOf(const qreal src[3], qreal res[3]) const { - const Vec r = localCoordinatesOf(Vec(src)); - for (int i=0; i<3 ; ++i) - res[i] = r[i]; + const Vec r = localCoordinatesOf(Vec(src)); + for (int i=0; i<3 ; ++i) + res[i] = r[i]; } - /*! Same as localInverseCoordinatesOf(), but with \c float parameters. */ -void Frame::getLocalInverseCoordinatesOf(const float src[3], float res[3]) const +/*! Same as localInverseCoordinatesOf(), but with \c qreal parameters. */ +void Frame::getLocalInverseCoordinatesOf(const qreal src[3], qreal res[3]) const { - const Vec r = localInverseCoordinatesOf(Vec(src)); - for (int i=0; i<3 ; ++i) - res[i] = r[i]; + const Vec r = localInverseCoordinatesOf(Vec(src)); + for (int i=0; i<3 ; ++i) + res[i] = r[i]; } -/*! Same as coordinatesOfIn(), but with \c float parameters. */ -void Frame::getCoordinatesOfIn(const float src[3], float res[3], const Frame* const in) const +/*! Same as coordinatesOfIn(), but with \c qreal parameters. */ +void Frame::getCoordinatesOfIn(const qreal src[3], qreal res[3], const Frame* const in) const { - const Vec r = coordinatesOfIn(Vec(src), in); - for (int i=0; i<3 ; ++i) - res[i] = r[i]; + const Vec r = coordinatesOfIn(Vec(src), in); + for (int i=0; i<3 ; ++i) + res[i] = r[i]; } -/*! Same as coordinatesOfFrom(), but with \c float parameters. */ -void Frame::getCoordinatesOfFrom(const float src[3], float res[3], const Frame* const from) const +/*! Same as coordinatesOfFrom(), but with \c qreal parameters. */ +void Frame::getCoordinatesOfFrom(const qreal src[3], qreal res[3], const Frame* const from) const { - const Vec r = coordinatesOfFrom(Vec(src), from); - for (int i=0; i<3 ; ++i) - res[i] = r[i]; + const Vec r = coordinatesOfFrom(Vec(src), from); + for (int i=0; i<3 ; ++i) + res[i] = r[i]; } @@ -833,10 +842,10 @@ void Frame::getCoordinatesOfFrom(const float src[3], float res[3], const Frame* illustration. */ Vec Frame::transformOf(const Vec& src) const { - if (referenceFrame()) - return localTransformOf(referenceFrame()->transformOf(src)); - else - return localTransformOf(src); + if (referenceFrame()) + return localTransformOf(referenceFrame()->transformOf(src)); + else + return localTransformOf(src); } /*! Returns the world transform of the vector whose coordinates in the Frame coordinate @@ -846,14 +855,14 @@ Vec Frame::transformOf(const Vec& src) const coordinates instead of 3D vectors. */ Vec Frame::inverseTransformOf(const Vec& src) const { - const Frame* fr = this; - Vec res = src; - while (fr != NULL) - { - res = fr->localInverseTransformOf(res); - fr = fr->referenceFrame(); - } - return res; + const Frame* fr = this; + Vec res = src; + while (fr != NULL) + { + res = fr->localInverseTransformOf(res); + fr = fr->referenceFrame(); + } + return res; } /*! Returns the Frame transform of a vector \p src defined in the referenceFrame() coordinate system @@ -862,7 +871,7 @@ Vec Frame::inverseTransformOf(const Vec& src) const localInverseTransformOf() performs the inverse transformation. See also localCoordinatesOf(). */ Vec Frame::localTransformOf(const Vec& src) const { - return rotation().inverseRotate(src); + return rotation().inverseRotate(src); } /*! Returns the referenceFrame() transform of a vector \p src defined in the Frame coordinate @@ -871,7 +880,7 @@ Vec Frame::localTransformOf(const Vec& src) const localTransformOf() performs the inverse transformation. See also localInverseCoordinatesOf(). */ Vec Frame::localInverseTransformOf(const Vec& src) const { - return rotation().rotate(src); + return rotation().rotate(src); } /*! Returns the Frame transform of the vector whose coordinates in the \p from coordinate system is \p @@ -880,13 +889,13 @@ Vec Frame::localInverseTransformOf(const Vec& src) const transformOfIn() performs the inverse transformation. */ Vec Frame::transformOfFrom(const Vec& src, const Frame* const from) const { - if (this == from) - return src; - else - if (referenceFrame()) - return localTransformOf(referenceFrame()->transformOfFrom(src, from)); - else - return localTransformOf(from->inverseTransformOf(src)); + if (this == from) + return src; + else + if (referenceFrame()) + return localTransformOf(referenceFrame()->transformOfFrom(src, from)); + else + return localTransformOf(from->inverseTransformOf(src)); } /*! Returns the \p in transform of the vector whose coordinates in the Frame coordinate system is \p @@ -895,70 +904,70 @@ Vec Frame::transformOfFrom(const Vec& src, const Frame* const from) const transformOfFrom() performs the inverse transformation. */ Vec Frame::transformOfIn(const Vec& src, const Frame* const in) const { - const Frame* fr = this; - Vec res = src; - while ((fr != NULL) && (fr != in)) - { - res = fr->localInverseTransformOf(res); - fr = fr->referenceFrame(); - } + const Frame* fr = this; + Vec res = src; + while ((fr != NULL) && (fr != in)) + { + res = fr->localInverseTransformOf(res); + fr = fr->referenceFrame(); + } - if (fr != in) - // in was not found in the branch of this, res is now expressed in the world - // coordinate system. Simply convert to in coordinate system. - res = in->transformOf(res); + if (fr != in) + // in was not found in the branch of this, res is now expressed in the world + // coordinate system. Simply convert to in coordinate system. + res = in->transformOf(res); - return res; + return res; } -///////////////// float[3] versions ////////////////////// +///////////////// qreal[3] versions ////////////////////// -/*! Same as transformOf(), but with \c float parameters. */ -void Frame::getTransformOf(const float src[3], float res[3]) const +/*! Same as transformOf(), but with \c qreal parameters. */ +void Frame::getTransformOf(const qreal src[3], qreal res[3]) const { - Vec r = transformOf(Vec(src)); - for (int i=0; i<3 ; ++i) - res[i] = r[i]; + Vec r = transformOf(Vec(src)); + for (int i=0; i<3 ; ++i) + res[i] = r[i]; } -/*! Same as inverseTransformOf(), but with \c float parameters. */ -void Frame::getInverseTransformOf(const float src[3], float res[3]) const +/*! Same as inverseTransformOf(), but with \c qreal parameters. */ +void Frame::getInverseTransformOf(const qreal src[3], qreal res[3]) const { - Vec r = inverseTransformOf(Vec(src)); - for (int i=0; i<3 ; ++i) - res[i] = r[i]; + Vec r = inverseTransformOf(Vec(src)); + for (int i=0; i<3 ; ++i) + res[i] = r[i]; } -/*! Same as localTransformOf(), but with \c float parameters. */ -void Frame::getLocalTransformOf(const float src[3], float res[3]) const +/*! Same as localTransformOf(), but with \c qreal parameters. */ +void Frame::getLocalTransformOf(const qreal src[3], qreal res[3]) const { - Vec r = localTransformOf(Vec(src)); - for (int i=0; i<3 ; ++i) - res[i] = r[i]; + Vec r = localTransformOf(Vec(src)); + for (int i=0; i<3 ; ++i) + res[i] = r[i]; } -/*! Same as localInverseTransformOf(), but with \c float parameters. */ -void Frame::getLocalInverseTransformOf(const float src[3], float res[3]) const +/*! Same as localInverseTransformOf(), but with \c qreal parameters. */ +void Frame::getLocalInverseTransformOf(const qreal src[3], qreal res[3]) const { - Vec r = localInverseTransformOf(Vec(src)); - for (int i=0; i<3 ; ++i) - res[i] = r[i]; + Vec r = localInverseTransformOf(Vec(src)); + for (int i=0; i<3 ; ++i) + res[i] = r[i]; } -/*! Same as transformOfIn(), but with \c float parameters. */ -void Frame::getTransformOfIn(const float src[3], float res[3], const Frame* const in) const +/*! Same as transformOfIn(), but with \c qreal parameters. */ +void Frame::getTransformOfIn(const qreal src[3], qreal res[3], const Frame* const in) const { - Vec r = transformOfIn(Vec(src), in); - for (int i=0; i<3 ; ++i) - res[i] = r[i]; + Vec r = transformOfIn(Vec(src), in); + for (int i=0; i<3 ; ++i) + res[i] = r[i]; } -/*! Same as transformOfFrom(), but with \c float parameters. */ -void Frame::getTransformOfFrom(const float src[3], float res[3], const Frame* const from) const +/*! Same as transformOfFrom(), but with \c qreal parameters. */ +void Frame::getTransformOfFrom(const qreal src[3], qreal res[3], const Frame* const from) const { - Vec r = transformOfFrom(Vec(src), from); - for (int i=0; i<3 ; ++i) - res[i] = r[i]; + Vec r = transformOfFrom(Vec(src), from); + for (int i=0; i<3 ; ++i) + res[i] = r[i]; } //////////////////////////// STATE ////////////////////////////// @@ -984,11 +993,11 @@ void Frame::getTransformOfFrom(const float src[3], float res[3], const Frame* co \attention The constraint() and referenceFrame() are not saved in the QDomElement. */ QDomElement Frame::domElement(const QString& name, QDomDocument& document) const { - // TODO: use translation and rotation instead when referenceFrame is coded... - QDomElement e = document.createElement(name); - e.appendChild(position().domElement("position", document)); - e.appendChild(orientation().domElement("orientation", document)); - return e; + // TODO: use translation and rotation instead when referenceFrame is coded... + QDomElement e = document.createElement(name); + e.appendChild(position().domElement("position", document)); + e.appendChild(orientation().domElement("orientation", document)); + return e; } /*! Restores the Frame state from a \c QDomElement created by domElement(). @@ -1001,23 +1010,23 @@ QDomElement Frame::domElement(const QString& name, QDomDocument& document) const unchanged. */ void Frame::initFromDOMElement(const QDomElement& element) { - // TODO: use translation and rotation instead when referenceFrame is coded... + // TODO: use translation and rotation instead when referenceFrame is coded... - // Reset default values. Attention: destroys constraint. - // *this = Frame(); - // This instead ? Better : what is not set is not changed. - // setPositionAndOrientation(Vec(), Quaternion()); + // Reset default values. Attention: destroys constraint. + // *this = Frame(); + // This instead ? Better : what is not set is not changed. + // setPositionAndOrientation(Vec(), Quaternion()); - QDomElement child=element.firstChild().toElement(); - while (!child.isNull()) - { - if (child.tagName() == "position") - setPosition(Vec(child)); - if (child.tagName() == "orientation") - setOrientation(Quaternion(child).normalized()); + QDomElement child=element.firstChild().toElement(); + while (!child.isNull()) + { + if (child.tagName() == "position") + setPosition(Vec(child)); + if (child.tagName() == "orientation") + setOrientation(Quaternion(child).normalized()); - child = child.nextSibling().toElement(); - } + child = child.nextSibling().toElement(); + } } ///////////////////////////////// ALIGN ///////////////////////////////// @@ -1031,10 +1040,11 @@ If, after this first rotation, two other axis are also almost parallel, a second performed. The two frames then have identical orientations, up to 90 degrees rotations. \p threshold measures how close two axis must be to be considered parallel. It is compared with the -absolute values of the dot product of the normalized axis. +absolute values of the dot product of the normalized axis. As a result, useful range is sqrt(2)/2 +(systematic alignment) to 1 (no alignment). When \p move is set to \c true, the Frame position() is also affected by the alignment. The new -Frame position() is such that the \p frame position (computed with coordinatesOf(), in the Frame +Frame's position() is such that the \p frame position (computed with coordinatesOf(), in the Frame coordinates system) does not change. \p frame may be \c NULL and then represents the world coordinate system (same convention than for @@ -1042,81 +1052,78 @@ the referenceFrame()). The rotation (and translation when \p move is \c true) applied to the Frame are filtered by the possible constraint(). */ -void Frame::alignWithFrame(const Frame* const frame, bool move, float threshold) -{ - Vec directions[2][3]; - for (int d=0; d<3; ++d) - { - Vec dir((d==0)? 1.0 : 0.0, (d==1)? 1.0 : 0.0, (d==2)? 1.0 : 0.0); - if (frame) - directions[0][d] = frame->inverseTransformOf(dir); - else - directions[0][d] = dir; - directions[1][d] = inverseTransformOf(dir); - } - - float maxProj = 0.0f; - float proj; - unsigned short index[2]; - index[0] = index[1] = 0; - for (int i=0; i<3; ++i) - for (int j=0; j<3; ++j) - if ( (proj=fabs(directions[0][i]*directions[1][j])) >= maxProj ) +void Frame::alignWithFrame(const Frame* const frame, bool move, qreal threshold) +{ + Vec directions[2][3]; + for (unsigned short d=0; d<3; ++d) { - index[0] = i; - index[1] = j; - maxProj = proj; + Vec dir((d==0)? 1.0 : 0.0, (d==1)? 1.0 : 0.0, (d==2)? 1.0 : 0.0); + if (frame) + directions[0][d] = frame->inverseTransformOf(dir); + else + directions[0][d] = dir; + directions[1][d] = inverseTransformOf(dir); } - Frame old; - old=*this; - - float coef = directions[0][index[0]] * directions[1][index[1]]; - if (fabs(coef) >= threshold) - { - const Vec axis = cross(directions[0][index[0]], directions[1][index[1]]); - float angle = asin(axis.norm()); - if (coef >= 0.0) - angle = -angle; - // setOrientation(Quaternion(axis, angle) * orientation()); - rotate(rotation().inverse() * Quaternion(axis, angle) * orientation()); - - // Try to align an other axis direction - unsigned short d = (index[1]+1) % 3; - Vec dir((d==0)? 1.0 : 0.0, (d==1)? 1.0 : 0.0, (d==2)? 1.0 : 0.0); - dir = inverseTransformOf(dir); - - float max = 0.0f; - for (int i=0; i<3; ++i) + qreal maxProj = 0.0; + qreal proj; + unsigned short index[2]; + index[0] = index[1] = 0; + for (unsigned short i=0; i<3; ++i) + for (unsigned short j=0; j<3; ++j) + if ( (proj=fabs(directions[0][i]*directions[1][j])) >= maxProj ) + { + index[0] = i; + index[1] = j; + maxProj = proj; + } + + Frame old; + old=*this; + + qreal coef = directions[0][index[0]] * directions[1][index[1]]; + if (fabs(coef) >= threshold) { - float proj = fabs(directions[0][i]*dir); - if (proj > max) - { - index[0] = i; - max = proj; - } + const Vec axis = cross(directions[0][index[0]], directions[1][index[1]]); + qreal angle = asin(axis.norm()); + if (coef >= 0.0) + angle = -angle; + rotate(rotation().inverse() * Quaternion(axis, angle) * orientation()); + + // Try to align an other axis direction + unsigned short d = (index[1]+1) % 3; + Vec dir((d==0)? 1.0 : 0.0, (d==1)? 1.0 : 0.0, (d==2)? 1.0 : 0.0); + dir = inverseTransformOf(dir); + + qreal max = 0.0; + for (unsigned short i=0; i<3; ++i) + { + qreal proj = fabs(directions[0][i]*dir); + if (proj > max) + { + index[0] = i; + max = proj; + } + } + + if (max >= threshold) + { + const Vec axis = cross(directions[0][index[0]], dir); + qreal angle = asin(axis.norm()); + if (directions[0][index[0]] * dir >= 0.0) + angle = -angle; + rotate(rotation().inverse() * Quaternion(axis, angle) * orientation()); + } } - if (max >= threshold) + if (move) { - const Vec axis = cross(directions[0][index[0]], dir); - float angle = asin(axis.norm()); - if (directions[0][index[0]] * dir >= 0.0) - angle = -angle; - // setOrientation(Quaternion(axis, angle) * orientation()); - rotate(rotation().inverse() * Quaternion(axis, angle) * orientation()); - } - } + Vec center; + if (frame) + center = frame->position(); - if (move) - { - Vec center; - if (frame) - center = frame->position(); - - // setPosition(center - orientation().rotate(old.coordinatesOf(center))); - translate(center - orientation().rotate(old.coordinatesOf(center)) - translation()); - } + translate(center - orientation().rotate(old.coordinatesOf(center)) - translation()); + } } /*! Translates the Frame so that its position() lies on the line defined by \p origin and \p @@ -1125,13 +1132,13 @@ void Frame::alignWithFrame(const Frame* const frame, bool move, float threshold) Simply uses an orthogonal projection. \p direction does not need to be normalized. */ void Frame::projectOnLine(const Vec& origin, const Vec& direction) { - // If you are trying to find a bug here, because of memory problems, you waste your time. - // This is a bug in the gcc 3.3 compiler. Compile the library in debug mode and test. - // Uncommenting this line also seems to solve the problem. Horrible. - // cout << "position = " << position() << endl; - // If you found a problem or are using a different compiler, please let me know. - const Vec shift = origin - position(); - Vec proj = shift; - proj.projectOnAxis(direction); - translate(shift-proj); + // If you are trying to find a bug here, because of memory problems, you waste your time. + // This is a bug in the gcc 3.3 compiler. Compile the library in debug mode and test. + // Uncommenting this line also seems to solve the problem. Horrible. + // cout << "position = " << position() << endl; + // If you found a problem or are using a different compiler, please let me know. + const Vec shift = origin - position(); + Vec proj = shift; + proj.projectOnAxis(direction); + translate(shift-proj); } diff --git a/octovis/src/extern/QGLViewer/frame.h b/octovis/src/extern/QGLViewer/frame.h index 5b31d1a5..2b88540a 100644 --- a/octovis/src/extern/QGLViewer/frame.h +++ b/octovis/src/extern/QGLViewer/frame.h @@ -1,8 +1,8 @@ /**************************************************************************** - Copyright (C) 2002-2013 Gilles Debunne. All rights reserved. + Copyright (C) 2002-2014 Gilles Debunne. All rights reserved. - This file is part of the QGLViewer library version 2.4.0. + This file is part of the QGLViewer library version 2.6.3. http://www.libqglviewer.com - contact@libqglviewer.com @@ -23,19 +23,14 @@ #ifndef QGLVIEWER_FRAME_H #define QGLVIEWER_FRAME_H -#if QT_VERSION >= 0x040000 -# include -# include -#else -# include -# include -#endif +#include +#include #include "constraint.h" // #include "GL/gl.h" is now included in config.h for ease of configuration namespace qglviewer { - /*! \brief The Frame class represents a coordinate system, defined by a position and an +/*! \brief The Frame class represents a coordinate system, defined by a position and an orientation. \class Frame frame.h QGLViewer/frame.h A Frame is a 3D coordinate system, represented by a position() and an orientation(). The order of @@ -123,299 +118,297 @@ namespace qglviewer { Frame (and hence an object) can be manipulated in the scene with the mouse. \nosubgrouping */ - class QGLVIEWER_EXPORT Frame : public QObject - { - Q_OBJECT - - public: - Frame(); +class QGLVIEWER_EXPORT Frame : public QObject +{ + Q_OBJECT - /*! Virtual destructor. Empty. */ - virtual ~Frame() {}; +public: + Frame(); - Frame(const Frame& frame); - Frame& operator=(const Frame& frame); + /*! Virtual destructor. Empty. */ + virtual ~Frame() {} - Q_SIGNALS: - /*! This signal is emitted whenever the position() or the orientation() of the Frame is modified. + Frame(const Frame& frame); + Frame& operator=(const Frame& frame); - Connect this signal to any object that must be notified: - \code - QObject::connect(myFrame, SIGNAL(modified()), myObject, SLOT(update())); - \endcode - Use the QGLViewer::QGLViewerPool() to connect the signal to all the viewers. +Q_SIGNALS: + /*! This signal is emitted whenever the position() or the orientation() of the Frame is modified. - \note If your Frame is part of a Frame hierarchy (see referenceFrame()), a modification of one - of the parents of this Frame will \e not emit this signal. Use code like this to change this - behavior (you can do this recursively for all the referenceFrame() until the \c NULL world root - frame is encountered): - \code - // Emits the Frame modified() signal when its referenceFrame() is modified(). - connect(myFrame->referenceFrame(), SIGNAL(modified()), myFrame, SIGNAL(modified())); - \endcode + Connect this signal to any object that must be notified: + \code + QObject::connect(myFrame, SIGNAL(modified()), myObject, SLOT(update())); + \endcode + Use the QGLViewer::QGLViewerPool() to connect the signal to all the viewers. - \attention Connecting this signal to a QGLWidget::updateGL() slot (or a method that calls it) - will prevent you from modifying the Frame \e inside your QGLViewer::draw() method as it would - result in an infinite loop. However, QGLViewer::draw() should not modify the scene. + \note If your Frame is part of a Frame hierarchy (see referenceFrame()), a modification of one + of the parents of this Frame will \e not emit this signal. Use code like this to change this + behavior (you can do this recursively for all the referenceFrame() until the \c NULL world root + frame is encountered): + \code + // Emits the Frame modified() signal when its referenceFrame() is modified(). + connect(myFrame->referenceFrame(), SIGNAL(modified()), myFrame, SIGNAL(modified())); + \endcode - \note For efficiency reasons, this signal is emitted even if the Frame is not actually modified, for - instance with translate(Vec(0,0,0)) or setPosition(position()). */ - void modified(); + \attention Connecting this signal to a QGLWidget::update() slot (or a method that calls it) + will prevent you from modifying the Frame \e inside your QGLViewer::draw() method as it would + result in an infinite loop. However, QGLViewer::draw() should not modify the scene. - /*! This signal is emitted when the Frame is interpolated by a KeyFrameInterpolator. + \note Note that this signal might be emitted even if the Frame is not actually modified, for + instance after a translate(Vec(0,0,0)) or a setPosition(position()). */ + void modified(); - See the KeyFrameInterpolator documentation for details. + /*! This signal is emitted when the Frame is interpolated by a KeyFrameInterpolator. - If a KeyFrameInterpolator is used to successively interpolate several Frames in your scene, - connect the KeyFrameInterpolator::interpolated() signal instead (identical, but independent of - the interpolated Frame). */ - void interpolated(); + See the KeyFrameInterpolator documentation for details. - public: - /*! @name World coordinates position and orientation */ - //@{ - Frame(const Vec& position, const Quaternion& orientation); + If a KeyFrameInterpolator is used to successively interpolate several Frames in your scene, + connect the KeyFrameInterpolator::interpolated() signal instead (identical, but independent of + the interpolated Frame). */ + void interpolated(); - void setPosition(const Vec& position); - void setPosition(float x, float y, float z); - void setPositionWithConstraint(Vec& position); - - void setOrientation(const Quaternion& orientation); - void setOrientation(double q0, double q1, double q2, double q3); - void setOrientationWithConstraint(Quaternion& orientation); - - void setPositionAndOrientation(const Vec& position, const Quaternion& orientation); - void setPositionAndOrientationWithConstraint(Vec& position, Quaternion& orientation); - - /*! Returns the position of the Frame, defined in the world coordinate system. See also - orientation(), setPosition() and translation(). */ - Vec position() const { return inverseCoordinatesOf(Vec(0.0,0.0,0.0)); }; - Quaternion orientation() const; - - void getPosition(float& x, float& y, float& z) const; - void getOrientation(double& q0, double& q1, double& q2, double& q3) const; - //@} +public: + /*! @name World coordinates position and orientation */ + //@{ + Frame(const Vec& position, const Quaternion& orientation); + void setPosition(const Vec& position); + void setPosition(qreal x, qreal y, qreal z); + void setPositionWithConstraint(Vec& position); - public: - /*! @name Local translation and rotation w/r reference Frame */ - //@{ - /*! Sets the translation() of the frame, locally defined with respect to the referenceFrame(). - Emits the modified() signal. - - Use setPosition() to define the world coordinates position(). Use - setTranslationWithConstraint() to take into account the potential constraint() of the Frame. */ - void setTranslation(const Vec& translation) { t_ = translation; Q_EMIT modified(); }; - void setTranslation(float x, float y, float z); - void setTranslationWithConstraint(Vec& translation); - - /*! Set the current rotation Quaternion. See rotation() and the different Quaternion - constructors. Emits the modified() signal. See also setTranslation() and - setRotationWithConstraint(). */ - - /*! Sets the rotation() of the Frame, locally defined with respect to the referenceFrame(). - Emits the modified() signal. - - Use setOrientation() to define the world coordinates orientation(). The potential - constraint() of the Frame is not taken into account, use setRotationWithConstraint() - instead. */ - void setRotation(const Quaternion& rotation) { q_ = rotation; Q_EMIT modified(); }; - void setRotation(double q0, double q1, double q2, double q3); - void setRotationWithConstraint(Quaternion& rotation); - - void setTranslationAndRotation(const Vec& translation, const Quaternion& rotation); - void setTranslationAndRotationWithConstraint(Vec& translation, Quaternion& rotation); - - /*! Returns the Frame translation, defined with respect to the referenceFrame(). - - Use position() to get the result in the world coordinates. These two values are identical - when the referenceFrame() is \c NULL (default). - - See also setTranslation() and setTranslationWithConstraint(). */ - Vec translation() const { return t_; }; - /*! Returns the Frame rotation, defined with respect to the referenceFrame(). - - Use orientation() to get the result in the world coordinates. These two values are identical - when the referenceFrame() is \c NULL (default). - - See also setRotation() and setRotationWithConstraint(). */ - - /*! Returns the current Quaternion orientation. See setRotation(). */ - Quaternion rotation() const { return q_; }; - - void getTranslation(float& x, float& y, float& z) const; - void getRotation(double& q0, double& q1, double& q2, double& q3) const; - //@} - - public: - /*! @name Frame hierarchy */ - //@{ - /*! Returns the reference Frame, in which coordinates system the Frame is defined. - - The translation() and rotation() of the Frame are defined with respect to the referenceFrame() - coordinate system. A \c NULL referenceFrame() (default value) means that the Frame is defined in - the world coordinate system. - - Use position() and orientation() to recursively convert values along the referenceFrame() chain - and to get values expressed in the world coordinate system. The values match when the - referenceFrame() is \c NULL. - - Use setReferenceFrame() to set this value and create a Frame hierarchy. Convenient functions - allow you to convert 3D coordinates from one Frame to an other: see coordinatesOf(), - localCoordinatesOf(), coordinatesOfIn() and their inverse functions. - - Vectors can also be converted using transformOf(), transformOfIn, localTransformOf() and their - inverse functions. */ - const Frame* referenceFrame() const { return referenceFrame_; }; - void setReferenceFrame(const Frame* const refFrame); - bool settingAsReferenceFrameWillCreateALoop(const Frame* const frame); - //@} - - - /*! @name Frame modification */ - //@{ - void translate(Vec& t); - void translate(const Vec& t); - // Some compilers complain about "overloading cannot distinguish from previous declaration" - // Simply comment out the following method and its associated implementation - void translate(float x, float y, float z); - void translate(float& x, float& y, float& z); - - void rotate(Quaternion& q); - void rotate(const Quaternion& q); - // Some compilers complain about "overloading cannot distinguish from previous declaration" - // Simply comment out the following method and its associated implementation - void rotate(double q0, double q1, double q2, double q3); - void rotate(double& q0, double& q1, double& q2, double& q3); - - void rotateAroundPoint(Quaternion& rotation, const Vec& point); - void rotateAroundPoint(const Quaternion& rotation, const Vec& point); - - void alignWithFrame(const Frame* const frame, bool move=false, float threshold=0.85f); - void projectOnLine(const Vec& origin, const Vec& direction); - //@} - - - /*! @name Coordinate system transformation of 3D coordinates */ - //@{ - Vec coordinatesOf(const Vec& src) const; - Vec inverseCoordinatesOf(const Vec& src) const; - Vec localCoordinatesOf(const Vec& src) const; - Vec localInverseCoordinatesOf(const Vec& src) const; - Vec coordinatesOfIn(const Vec& src, const Frame* const in) const; - Vec coordinatesOfFrom(const Vec& src, const Frame* const from) const; - - void getCoordinatesOf(const float src[3], float res[3]) const; - void getInverseCoordinatesOf(const float src[3], float res[3]) const; - void getLocalCoordinatesOf(const float src[3], float res[3]) const; - void getLocalInverseCoordinatesOf(const float src[3], float res[3]) const; - void getCoordinatesOfIn(const float src[3], float res[3], const Frame* const in) const; - void getCoordinatesOfFrom(const float src[3], float res[3], const Frame* const from) const; - //@} - - /*! @name Coordinate system transformation of vectors */ - // A frame is as a new coordinate system, defined with respect to a reference frame (the world - // coordinate system by default, see the "Composition of frame" section). - - // The transformOf() (resp. inverseTransformOf()) functions transform a 3D vector from (resp. - // to) the world coordinates system. This section defines the 3D vector transformation - // functions. See the Coordinate system transformation of 3D points above for the transformation - // of 3D points. The difference between the two sets of functions is simple: for vectors, only - // the rotational part of the transformations is taken into account, while translation is also - // considered for 3D points. - - // The length of the resulting transformed vector is identical to the one of the source vector - // for all the described functions. - - // When local is prepended to the names of the functions, the functions simply transform from - // (and to) the reference frame. - - // When In (resp. From) is appended to the names, the functions transform from (resp. To) the - // frame that is given as an argument. The frame does not need to be in the same branch or the - // hierarchical tree, and can be \c NULL (the world coordinates system). - - // Combining any of these functions with its inverse (in any order) leads to the identity. - //@{ - Vec transformOf(const Vec& src) const; - Vec inverseTransformOf(const Vec& src) const; - Vec localTransformOf(const Vec& src) const; - Vec localInverseTransformOf(const Vec& src) const; - Vec transformOfIn(const Vec& src, const Frame* const in) const; - Vec transformOfFrom(const Vec& src, const Frame* const from) const; - - void getTransformOf(const float src[3], float res[3]) const; - void getInverseTransformOf(const float src[3], float res[3]) const; - void getLocalTransformOf(const float src[3], float res[3]) const; - void getLocalInverseTransformOf(const float src[3], float res[3]) const; - void getTransformOfIn(const float src[3], float res[3], const Frame* const in) const; - void getTransformOfFrom(const float src[3], float res[3], const Frame* const from) const; - //@} - - - /*! @name Constraint on the displacement */ - //@{ - /*! Returns the current constraint applied to the Frame. - - A \c NULL value (default) means that no Constraint is used to filter Frame translation and - rotation. See the Constraint class documentation for details. - - You may have to use a \c dynamic_cast to convert the result to a Constraint derived class. */ - Constraint* constraint() const { return constraint_; } - /*! Sets the constraint() attached to the Frame. - - A \c NULL value means no constraint. The previous constraint() should be deleted by the calling - method if needed. */ - void setConstraint(Constraint* const constraint) { constraint_ = constraint; } - //@} - - /*! @name Associated matrices */ - //@{ - public: - const GLdouble* matrix() const; - void getMatrix(GLdouble m[4][4]) const; - void getMatrix(GLdouble m[16]) const; - - const GLdouble* worldMatrix() const; - void getWorldMatrix(GLdouble m[4][4]) const; - void getWorldMatrix(GLdouble m[16]) const; - - void setFromMatrix(const GLdouble m[4][4]); - void setFromMatrix(const GLdouble m[16]); - //@} - - /*! @name Inversion of the transformation */ - //@{ - Frame inverse() const; - /*! Returns the inverse() of the Frame world transformation. - - The orientation() of the new Frame is the Quaternion::inverse() of the original orientation. - Its position() is the negated and inverse rotated image of the original position. - - The result Frame has a \c NULL referenceFrame() and a \c NULL constraint(). - - Use inverse() for a local (i.e. with respect to referenceFrame()) transformation inverse. */ - Frame worldInverse() const { return Frame(-(orientation().inverseRotate(position())), orientation().inverse()); } - //@} - - /*! @name XML representation */ - //@{ - public: - virtual QDomElement domElement(const QString& name, QDomDocument& document) const; - public Q_SLOTS: - virtual void initFromDOMElement(const QDomElement& element); - //@} - - private: - // P o s i t i o n a n d o r i e n t a t i o n - Vec t_; - Quaternion q_; - - // C o n s t r a i n t s - Constraint* constraint_; - - // F r a m e c o m p o s i t i o n - const Frame* referenceFrame_; - }; + void setOrientation(const Quaternion& orientation); + void setOrientation(qreal q0, qreal q1, qreal q2, qreal q3); + void setOrientationWithConstraint(Quaternion& orientation); + + void setPositionAndOrientation(const Vec& position, const Quaternion& orientation); + void setPositionAndOrientationWithConstraint(Vec& position, Quaternion& orientation); + + Vec position() const; + Quaternion orientation() const; + + void getPosition(qreal& x, qreal& y, qreal& z) const; + void getOrientation(qreal& q0, qreal& q1, qreal& q2, qreal& q3) const; + //@} + + +public: + /*! @name Local translation and rotation w/r reference Frame */ + //@{ + /*! Sets the translation() of the frame, locally defined with respect to the referenceFrame(). + Emits the modified() signal. + + Use setPosition() to define the world coordinates position(). Use + setTranslationWithConstraint() to take into account the potential constraint() of the Frame. */ + void setTranslation(const Vec& translation) { t_ = translation; Q_EMIT modified(); } + void setTranslation(qreal x, qreal y, qreal z); + void setTranslationWithConstraint(Vec& translation); + + /*! Set the current rotation Quaternion. See rotation() and the different Quaternion + constructors. Emits the modified() signal. See also setTranslation() and + setRotationWithConstraint(). */ + + /*! Sets the rotation() of the Frame, locally defined with respect to the referenceFrame(). + Emits the modified() signal. + + Use setOrientation() to define the world coordinates orientation(). The potential + constraint() of the Frame is not taken into account, use setRotationWithConstraint() + instead. */ + void setRotation(const Quaternion& rotation) { q_ = rotation; Q_EMIT modified(); } + void setRotation(qreal q0, qreal q1, qreal q2, qreal q3); + void setRotationWithConstraint(Quaternion& rotation); + + void setTranslationAndRotation(const Vec& translation, const Quaternion& rotation); + void setTranslationAndRotationWithConstraint(Vec& translation, Quaternion& rotation); + + /*! Returns the Frame translation, defined with respect to the referenceFrame(). + + Use position() to get the result in the world coordinates. These two values are identical + when the referenceFrame() is \c NULL (default). + + See also setTranslation() and setTranslationWithConstraint(). */ + Vec translation() const { return t_; } + /*! Returns the Frame rotation, defined with respect to the referenceFrame(). + + Use orientation() to get the result in the world coordinates. These two values are identical + when the referenceFrame() is \c NULL (default). + + See also setRotation() and setRotationWithConstraint(). */ + + /*! Returns the current Quaternion orientation. See setRotation(). */ + Quaternion rotation() const { return q_; } + + void getTranslation(qreal& x, qreal& y, qreal& z) const; + void getRotation(qreal& q0, qreal& q1, qreal& q2, qreal& q3) const; + //@} + +public: + /*! @name Frame hierarchy */ + //@{ + /*! Returns the reference Frame, in which coordinates system the Frame is defined. + + The translation() and rotation() of the Frame are defined with respect to the referenceFrame() + coordinate system. A \c NULL referenceFrame() (default value) means that the Frame is defined in + the world coordinate system. + + Use position() and orientation() to recursively convert values along the referenceFrame() chain + and to get values expressed in the world coordinate system. The values match when the + referenceFrame() is \c NULL. + + Use setReferenceFrame() to set this value and create a Frame hierarchy. Convenient functions + allow you to convert 3D coordinates from one Frame to an other: see coordinatesOf(), + localCoordinatesOf(), coordinatesOfIn() and their inverse functions. + + Vectors can also be converted using transformOf(), transformOfIn, localTransformOf() and their + inverse functions. */ + const Frame* referenceFrame() const { return referenceFrame_; } + void setReferenceFrame(const Frame* const refFrame); + bool settingAsReferenceFrameWillCreateALoop(const Frame* const frame); + //@} + + + /*! @name Frame modification */ + //@{ + void translate(Vec& t); + void translate(const Vec& t); + // Some compilers complain about "overloading cannot distinguish from previous declaration" + // Simply comment out the following method and its associated implementation + void translate(qreal x, qreal y, qreal z); + void translate(qreal& x, qreal& y, qreal& z); + + void rotate(Quaternion& q); + void rotate(const Quaternion& q); + // Some compilers complain about "overloading cannot distinguish from previous declaration" + // Simply comment out the following method and its associated implementation + void rotate(qreal q0, qreal q1, qreal q2, qreal q3); + void rotate(qreal& q0, qreal& q1, qreal& q2, qreal& q3); + + void rotateAroundPoint(Quaternion& rotation, const Vec& point); + void rotateAroundPoint(const Quaternion& rotation, const Vec& point); + + void alignWithFrame(const Frame* const frame, bool move=false, qreal threshold=0.0); + void projectOnLine(const Vec& origin, const Vec& direction); + //@} + + + /*! @name Coordinate system transformation of 3D coordinates */ + //@{ + Vec coordinatesOf(const Vec& src) const; + Vec inverseCoordinatesOf(const Vec& src) const; + Vec localCoordinatesOf(const Vec& src) const; + Vec localInverseCoordinatesOf(const Vec& src) const; + Vec coordinatesOfIn(const Vec& src, const Frame* const in) const; + Vec coordinatesOfFrom(const Vec& src, const Frame* const from) const; + + void getCoordinatesOf(const qreal src[3], qreal res[3]) const; + void getInverseCoordinatesOf(const qreal src[3], qreal res[3]) const; + void getLocalCoordinatesOf(const qreal src[3], qreal res[3]) const; + void getLocalInverseCoordinatesOf(const qreal src[3], qreal res[3]) const; + void getCoordinatesOfIn(const qreal src[3], qreal res[3], const Frame* const in) const; + void getCoordinatesOfFrom(const qreal src[3], qreal res[3], const Frame* const from) const; + //@} + + /*! @name Coordinate system transformation of vectors */ + // A frame is as a new coordinate system, defined with respect to a reference frame (the world + // coordinate system by default, see the "Composition of frame" section). + + // The transformOf() (resp. inverseTransformOf()) functions transform a 3D vector from (resp. + // to) the world coordinates system. This section defines the 3D vector transformation + // functions. See the Coordinate system transformation of 3D points above for the transformation + // of 3D points. The difference between the two sets of functions is simple: for vectors, only + // the rotational part of the transformations is taken into account, while translation is also + // considered for 3D points. + + // The length of the resulting transformed vector is identical to the one of the source vector + // for all the described functions. + + // When local is prepended to the names of the functions, the functions simply transform from + // (and to) the reference frame. + + // When In (resp. From) is appended to the names, the functions transform from (resp. To) the + // frame that is given as an argument. The frame does not need to be in the same branch or the + // hierarchical tree, and can be \c NULL (the world coordinates system). + + // Combining any of these functions with its inverse (in any order) leads to the identity. + //@{ + Vec transformOf(const Vec& src) const; + Vec inverseTransformOf(const Vec& src) const; + Vec localTransformOf(const Vec& src) const; + Vec localInverseTransformOf(const Vec& src) const; + Vec transformOfIn(const Vec& src, const Frame* const in) const; + Vec transformOfFrom(const Vec& src, const Frame* const from) const; + + void getTransformOf(const qreal src[3], qreal res[3]) const; + void getInverseTransformOf(const qreal src[3], qreal res[3]) const; + void getLocalTransformOf(const qreal src[3], qreal res[3]) const; + void getLocalInverseTransformOf(const qreal src[3], qreal res[3]) const; + void getTransformOfIn(const qreal src[3], qreal res[3], const Frame* const in) const; + void getTransformOfFrom(const qreal src[3], qreal res[3], const Frame* const from) const; + //@} + + + /*! @name Constraint on the displacement */ + //@{ + /*! Returns the current constraint applied to the Frame. + + A \c NULL value (default) means that no Constraint is used to filter Frame translation and + rotation. See the Constraint class documentation for details. + + You may have to use a \c dynamic_cast to convert the result to a Constraint derived class. */ + Constraint* constraint() const { return constraint_; } + /*! Sets the constraint() attached to the Frame. + + A \c NULL value means no constraint. The previous constraint() should be deleted by the calling + method if needed. */ + void setConstraint(Constraint* const constraint) { constraint_ = constraint; } + //@} + + /*! @name Associated matrices */ + //@{ +public: + const GLdouble* matrix() const; + void getMatrix(GLdouble m[4][4]) const; + void getMatrix(GLdouble m[16]) const; + + const GLdouble* worldMatrix() const; + void getWorldMatrix(GLdouble m[4][4]) const; + void getWorldMatrix(GLdouble m[16]) const; + + void setFromMatrix(const GLdouble m[4][4]); + void setFromMatrix(const GLdouble m[16]); + //@} + + /*! @name Inversion of the transformation */ + //@{ + Frame inverse() const; + /*! Returns the inverse() of the Frame world transformation. + + The orientation() of the new Frame is the Quaternion::inverse() of the original orientation. + Its position() is the negated and inverse rotated image of the original position. + + The result Frame has a \c NULL referenceFrame() and a \c NULL constraint(). + + Use inverse() for a local (i.e. with respect to referenceFrame()) transformation inverse. */ + Frame worldInverse() const { return Frame(-(orientation().inverseRotate(position())), orientation().inverse()); } + //@} + + /*! @name XML representation */ + //@{ +public: + virtual QDomElement domElement(const QString& name, QDomDocument& document) const; +public Q_SLOTS: + virtual void initFromDOMElement(const QDomElement& element); + //@} + +private: + // P o s i t i o n a n d o r i e n t a t i o n + Vec t_; + Quaternion q_; + + // C o n s t r a i n t s + Constraint* constraint_; + + // F r a m e c o m p o s i t i o n + const Frame* referenceFrame_; +}; } // namespace qglviewer diff --git a/octovis/src/extern/QGLViewer/keyFrameInterpolator.cpp b/octovis/src/extern/QGLViewer/keyFrameInterpolator.cpp index aa0de3af..480774bf 100644 --- a/octovis/src/extern/QGLViewer/keyFrameInterpolator.cpp +++ b/octovis/src/extern/QGLViewer/keyFrameInterpolator.cpp @@ -1,8 +1,8 @@ /**************************************************************************** - Copyright (C) 2002-2013 Gilles Debunne. All rights reserved. + Copyright (C) 2002-2014 Gilles Debunne. All rights reserved. - This file is part of the QGLViewer library version 2.4.0. + This file is part of the QGLViewer library version 2.6.3. http://www.libqglviewer.com - contact@libqglviewer.com @@ -26,11 +26,6 @@ using namespace qglviewer; using namespace std; -#if QT_VERSION < 0x040000 -// Patch for QPtrList / QList syntax difference -# define peekNext current -#endif - /*! Creates a KeyFrameInterpolator, with \p frame as associated frame(). The frame() can be set or changed using setFrame(). @@ -38,41 +33,34 @@ using namespace std; interpolationTime(), interpolationSpeed() and interpolationPeriod() are set to their default values. */ KeyFrameInterpolator::KeyFrameInterpolator(Frame* frame) - : frame_(NULL), period_(40), interpolationTime_(0.0), interpolationSpeed_(1.0), interpolationStarted_(false), - closedPath_(false), loopInterpolation_(false), pathIsValid_(false), valuesAreValid_(true), currentFrameValid_(false) - // #CONNECTION# Values cut pasted initFromDOMElement() + : frame_(NULL), period_(40), interpolationTime_(0.0), interpolationSpeed_(1.0), interpolationStarted_(false), + closedPath_(false), loopInterpolation_(false), pathIsValid_(false), valuesAreValid_(true), currentFrameValid_(false) + // #CONNECTION# Values cut pasted initFromDOMElement() { - setFrame(frame); -#if QT_VERSION < 0x040000 - keyFrame_.setAutoDelete(true); -#endif - for (int i=0; i<4; ++i) -#if QT_VERSION >= 0x040000 - currentFrame_[i] = new QMutableListIterator(keyFrame_); -#else - currentFrame_[i] = new QPtrListIterator(keyFrame_); -#endif - connect(&timer_, SIGNAL(timeout()), SLOT(update())); + setFrame(frame); + for (int i=0; i<4; ++i) + currentFrame_[i] = new QMutableListIterator(keyFrame_); + connect(&timer_, SIGNAL(timeout()), SLOT(update())); } /*! Virtual destructor. Clears the keyFrame path. */ KeyFrameInterpolator::~KeyFrameInterpolator() { - deletePath(); - for (int i=0; i<4; ++i) - delete currentFrame_[i]; + deletePath(); + for (int i=0; i<4; ++i) + delete currentFrame_[i]; } /*! Sets the frame() associated to the KeyFrameInterpolator. */ void KeyFrameInterpolator::setFrame(Frame* const frame) { - if (this->frame()) - disconnect(this, SIGNAL( interpolated() ), this->frame(), SIGNAL( interpolated() )); + if (this->frame()) + disconnect(this, SIGNAL( interpolated() ), this->frame(), SIGNAL( interpolated() )); - frame_ = frame; + frame_ = frame; - if (this->frame()) - connect(this, SIGNAL( interpolated() ), this->frame(), SIGNAL( interpolated() )); + if (this->frame()) + connect(this, SIGNAL( interpolated() ), this->frame(), SIGNAL( interpolated() )); } /*! Updates frame() state according to current interpolationTime(). Then adds @@ -83,35 +71,35 @@ void KeyFrameInterpolator::setFrame(Frame* const frame) lastTime(), unless loopInterpolation() is \c true. */ void KeyFrameInterpolator::update() { - interpolateAtTime(interpolationTime()); + interpolateAtTime(interpolationTime()); - interpolationTime_ += interpolationSpeed() * interpolationPeriod() / 1000.0; + interpolationTime_ += interpolationSpeed() * interpolationPeriod() / 1000.0; - if (interpolationTime() > keyFrame_.last()->time()) - { - if (loopInterpolation()) - setInterpolationTime(keyFrame_.first()->time() + interpolationTime_ - keyFrame_.last()->time()); - else + if (interpolationTime() > keyFrame_.last()->time()) { - // Make sure last KeyFrame is reached and displayed - interpolateAtTime(keyFrame_.last()->time()); - stopInterpolation(); + if (loopInterpolation()) + setInterpolationTime(keyFrame_.first()->time() + interpolationTime_ - keyFrame_.last()->time()); + else + { + // Make sure last KeyFrame is reached and displayed + interpolateAtTime(keyFrame_.last()->time()); + stopInterpolation(); + } + Q_EMIT endReached(); } - Q_EMIT endReached(); - } - else - if (interpolationTime() < keyFrame_.first()->time()) - { - if (loopInterpolation()) - setInterpolationTime(keyFrame_.last()->time() - keyFrame_.first()->time() + interpolationTime_); else - { - // Make sure first KeyFrame is reached and displayed - interpolateAtTime(keyFrame_.first()->time()); - stopInterpolation(); - } - Q_EMIT endReached(); - } + if (interpolationTime() < keyFrame_.first()->time()) + { + if (loopInterpolation()) + setInterpolationTime(keyFrame_.last()->time() - keyFrame_.first()->time() + interpolationTime_); + else + { + // Make sure first KeyFrame is reached and displayed + interpolateAtTime(keyFrame_.first()->time()); + stopInterpolation(); + } + Q_EMIT endReached(); + } } @@ -137,27 +125,27 @@ void KeyFrameInterpolator::update() or else the interpolation will naturally immediately stop. */ void KeyFrameInterpolator::startInterpolation(int period) { - if (period >= 0) - setInterpolationPeriod(period); - - if (!keyFrame_.isEmpty()) - { - if ((interpolationSpeed() > 0.0) && (interpolationTime() >= keyFrame_.last()->time())) - setInterpolationTime(keyFrame_.first()->time()); - if ((interpolationSpeed() < 0.0) && (interpolationTime() <= keyFrame_.first()->time())) - setInterpolationTime(keyFrame_.last()->time()); - timer_.start(interpolationPeriod()); - interpolationStarted_ = true; - update(); - } + if (period >= 0) + setInterpolationPeriod(period); + + if (!keyFrame_.isEmpty()) + { + if ((interpolationSpeed() > 0.0) && (interpolationTime() >= keyFrame_.last()->time())) + setInterpolationTime(keyFrame_.first()->time()); + if ((interpolationSpeed() < 0.0) && (interpolationTime() <= keyFrame_.first()->time())) + setInterpolationTime(keyFrame_.last()->time()); + timer_.start(interpolationPeriod()); + interpolationStarted_ = true; + update(); + } } /*! Stops an interpolation started with startInterpolation(). See interpolationIsStarted() and toggleInterpolation(). */ void KeyFrameInterpolator::stopInterpolation() { - timer_.stop(); - interpolationStarted_ = false; + timer_.stop(); + interpolationStarted_ = false; } @@ -167,8 +155,8 @@ If desired, call interpolateAtTime() after this method to actually move the fram firstTime(). */ void KeyFrameInterpolator::resetInterpolation() { - stopInterpolation(); - setInterpolationTime(firstTime()); + stopInterpolation(); + setInterpolationTime(firstTime()); } /*! Appends a new keyFrame to the path, with its associated \p time (in seconds). @@ -182,139 +170,137 @@ void KeyFrameInterpolator::resetInterpolation() \c NULL \p frame pointers are silently ignored. The keyFrameTime() has to be monotonously increasing over keyFrames. - Use addKeyFrame(const Frame&, float) to add keyFrame by values. */ -void KeyFrameInterpolator::addKeyFrame(const Frame* const frame, float time) + Use addKeyFrame(const Frame&, qreal) to add keyFrame by values. */ +void KeyFrameInterpolator::addKeyFrame(const Frame* const frame, qreal time) { - if (!frame) - return; - - if (keyFrame_.isEmpty()) - interpolationTime_ = time; - - if ( (!keyFrame_.isEmpty()) && (keyFrame_.last()->time() > time) ) - qWarning("Error in KeyFrameInterpolator::addKeyFrame: time is not monotone"); - else - keyFrame_.append(new KeyFrame(frame, time)); - connect(frame, SIGNAL(modified()), SLOT(invalidateValues())); - valuesAreValid_ = false; - pathIsValid_ = false; - currentFrameValid_ = false; - resetInterpolation(); + if (!frame) + return; + + if (keyFrame_.isEmpty()) + interpolationTime_ = time; + + if ( (!keyFrame_.isEmpty()) && (keyFrame_.last()->time() > time) ) + qWarning("Error in KeyFrameInterpolator::addKeyFrame: time is not monotone"); + else + keyFrame_.append(new KeyFrame(frame, time)); + connect(frame, SIGNAL(modified()), SLOT(invalidateValues())); + valuesAreValid_ = false; + pathIsValid_ = false; + currentFrameValid_ = false; + resetInterpolation(); } /*! Appends a new keyFrame to the path, with its associated \p time (in seconds). The path will use the current \p frame state. If you want the path to change when \p frame is modified, you need to pass a \e pointer to the Frame instead (see addKeyFrame(const Frame*, - float)). + qreal)). The keyFrameTime() have to be monotonously increasing over keyFrames. */ -void KeyFrameInterpolator::addKeyFrame(const Frame& frame, float time) +void KeyFrameInterpolator::addKeyFrame(const Frame& frame, qreal time) { - if (keyFrame_.isEmpty()) - interpolationTime_ = time; - - if ( (!keyFrame_.isEmpty()) && (keyFrame_.last()->time() > time) ) - qWarning("Error in KeyFrameInterpolator::addKeyFrame: time is not monotone"); - else - keyFrame_.append(new KeyFrame(frame, time)); - - valuesAreValid_ = false; - pathIsValid_ = false; - currentFrameValid_ = false; - resetInterpolation(); + if (keyFrame_.isEmpty()) + interpolationTime_ = time; + + if ( (!keyFrame_.isEmpty()) && (keyFrame_.last()->time() > time) ) + qWarning("Error in KeyFrameInterpolator::addKeyFrame: time is not monotone"); + else + keyFrame_.append(new KeyFrame(frame, time)); + + valuesAreValid_ = false; + pathIsValid_ = false; + currentFrameValid_ = false; + resetInterpolation(); } /*! Appends a new keyFrame to the path. - Same as addKeyFrame(const Frame* frame, float), except that the keyFrameTime() is set to the + Same as addKeyFrame(const Frame* frame, qreal), except that the keyFrameTime() is set to the previous keyFrameTime() plus one second (or 0.0 if there is no previous keyFrame). */ void KeyFrameInterpolator::addKeyFrame(const Frame* const frame) { - float time; - if (keyFrame_.isEmpty()) - time = 0.0; - else - time = lastTime() + 1.0; + qreal time; + if (keyFrame_.isEmpty()) + time = 0.0; + else + time = lastTime() + 1.0; - addKeyFrame(frame, time); + addKeyFrame(frame, time); } /*! Appends a new keyFrame to the path. - Same as addKeyFrame(const Frame& frame, float), except that the keyFrameTime() is automatically set + Same as addKeyFrame(const Frame& frame, qreal), except that the keyFrameTime() is automatically set to previous keyFrameTime() plus one second (or 0.0 if there is no previous keyFrame). */ void KeyFrameInterpolator::addKeyFrame(const Frame& frame) { - float time; - if (keyFrame_.isEmpty()) - time = 0.0; - else - time = keyFrame_.last()->time() + 1.0; + qreal time; + if (keyFrame_.isEmpty()) + time = 0.0; + else + time = keyFrame_.last()->time() + 1.0; - addKeyFrame(frame, time); + addKeyFrame(frame, time); } /*! Removes all keyFrames from the path. The numberOfKeyFrames() is set to 0. */ void KeyFrameInterpolator::deletePath() { - stopInterpolation(); -#if QT_VERSION >= 0x040000 - qDeleteAll(keyFrame_); -#endif - keyFrame_.clear(); - pathIsValid_ = false; - valuesAreValid_ = false; - currentFrameValid_ = false; + stopInterpolation(); + qDeleteAll(keyFrame_); + keyFrame_.clear(); + pathIsValid_ = false; + valuesAreValid_ = false; + currentFrameValid_ = false; } -static void drawCamera(float scale) +static void drawCamera(qreal scale) { - glDisable(GL_LIGHTING); - - const float halfHeight = scale * 0.07; - const float halfWidth = halfHeight * 1.3; - const float dist = halfHeight / tan(M_PI/8.0); - - const float arrowHeight = 1.5f * halfHeight; - const float baseHeight = 1.2f * halfHeight; - const float arrowHalfWidth = 0.5f * halfWidth; - const float baseHalfWidth = 0.3f * halfWidth; - - // Frustum outline - glPolygonMode(GL_FRONT_AND_BACK, GL_LINE); - glBegin(GL_LINE_STRIP); - glVertex3f(-halfWidth, halfHeight,-dist); - glVertex3f(-halfWidth,-halfHeight,-dist); - glVertex3f( 0.0f, 0.0f, 0.0f); - glVertex3f( halfWidth,-halfHeight,-dist); - glVertex3f(-halfWidth,-halfHeight,-dist); - glEnd(); - glBegin(GL_LINE_STRIP); - glVertex3f( halfWidth,-halfHeight,-dist); - glVertex3f( halfWidth, halfHeight,-dist); - glVertex3f( 0.0f, 0.0f, 0.0f); - glVertex3f(-halfWidth, halfHeight,-dist); - glVertex3f( halfWidth, halfHeight,-dist); - glEnd(); - - // Up arrow - glPolygonMode(GL_FRONT_AND_BACK, GL_FILL); - // Base - glBegin(GL_QUADS); - glVertex3f(-baseHalfWidth, halfHeight,-dist); - glVertex3f( baseHalfWidth, halfHeight,-dist); - glVertex3f( baseHalfWidth, baseHeight,-dist); - glVertex3f(-baseHalfWidth, baseHeight,-dist); - glEnd(); - - // Arrow - glBegin(GL_TRIANGLES); - glVertex3f( 0.0f, arrowHeight,-dist); - glVertex3f(-arrowHalfWidth, baseHeight, -dist); - glVertex3f( arrowHalfWidth, baseHeight, -dist); - glEnd(); + glDisable(GL_LIGHTING); + + const qreal halfHeight = scale * 0.07; + const qreal halfWidth = halfHeight * 1.3; + const qreal dist = halfHeight / tan(qreal(M_PI)/8.0); + + const qreal arrowHeight = 1.5 * halfHeight; + const qreal baseHeight = 1.2 * halfHeight; + const qreal arrowHalfWidth = 0.5 * halfWidth; + const qreal baseHalfWidth = 0.3 * halfWidth; + + // Frustum outline + glPolygonMode(GL_FRONT_AND_BACK, GL_LINE); + glBegin(GL_LINE_STRIP); + glVertex3d(-halfWidth, halfHeight,-dist); + glVertex3d(-halfWidth,-halfHeight,-dist); + glVertex3d( 0.0, 0.0, 0.0); + glVertex3d( halfWidth,-halfHeight,-dist); + glVertex3d(-halfWidth,-halfHeight,-dist); + glEnd(); + glBegin(GL_LINE_STRIP); + glVertex3d( halfWidth,-halfHeight,-dist); + glVertex3d( halfWidth, halfHeight,-dist); + glVertex3d( 0.0, 0.0, 0.0); + glVertex3d(-halfWidth, halfHeight,-dist); + glVertex3d( halfWidth, halfHeight,-dist); + glEnd(); + + // Up arrow + glPolygonMode(GL_FRONT_AND_BACK, GL_FILL); + // Base + glBegin(GL_QUADS); + glVertex3d(-baseHalfWidth, halfHeight,-dist); + glVertex3d( baseHalfWidth, halfHeight,-dist); + glVertex3d( baseHalfWidth, baseHeight,-dist); + glVertex3d(-baseHalfWidth, baseHeight,-dist); + glEnd(); + + // Arrow + glBegin(GL_TRIANGLES); + glVertex3d( 0.0, arrowHeight,-dist); + glVertex3d(-arrowHalfWidth, baseHeight, -dist); + glVertex3d( arrowHalfWidth, baseHeight, -dist); + glEnd(); } /*! Draws the path used to interpolate the frame(). @@ -348,169 +334,120 @@ static void drawCamera(float scale) drawPathModifyGLState(mask, nbFrames, scale); glPopAttrib(); \endcode */ -void KeyFrameInterpolator::drawPath(int mask, int nbFrames, float scale) +void KeyFrameInterpolator::drawPath(int mask, int nbFrames, qreal scale) { - const int nbSteps = 30; - if (!pathIsValid_) - { - path_.clear(); -#if QT_VERSION < 0x040000 - path_.reserve(nbSteps*keyFrame_.count()); -#endif - - if (keyFrame_.isEmpty()) - return; - - if (!valuesAreValid_) - updateModifiedFrameValues(); - - if (keyFrame_.first() == keyFrame_.last()) - path_.push_back(Frame(keyFrame_.first()->position(), keyFrame_.first()->orientation())); - else + const int nbSteps = 30; + if (!pathIsValid_) { - static Frame fr; - KeyFrame* kf_[4]; - kf_[0] = keyFrame_.first(); - kf_[1] = kf_[0]; -#if QT_VERSION >= 0x040000 - int index = 1; - kf_[2] = (index < keyFrame_.size()) ? keyFrame_.at(index) : NULL; - index++; - kf_[3] = (index < keyFrame_.size()) ? keyFrame_.at(index) : NULL; -#else - kf_[2] = keyFrame_.next(); - kf_[3] = keyFrame_.next(); -#endif - - while (kf_[2]) - { - Vec diff = kf_[2]->position() - kf_[1]->position(); - Vec v1 = 3.0 * diff - 2.0 * kf_[1]->tgP() - kf_[2]->tgP(); - Vec v2 = -2.0 * diff + kf_[1]->tgP() + kf_[2]->tgP(); - - // cout << kf_[0]->time() << " , " << kf_[1]->time() << " , " << kf_[2]->time() << " , " << kf_[3]->time() << endl; - for (int step=0; step(nbSteps); - fr.setPosition(kf_[1]->position() + alpha * (kf_[1]->tgP() + alpha * (v1+alpha*v2))); - fr.setOrientation(Quaternion::squad(kf_[1]->orientation(), kf_[1]->tgQ(), kf_[2]->tgQ(), kf_[2]->orientation(), alpha)); - path_.push_back(fr); - } + path_.clear(); - // Shift - kf_[0] = kf_[1]; - kf_[1] = kf_[2]; - kf_[2] = kf_[3]; -#if QT_VERSION >= 0x040000 - index++; - kf_[3] = (index < keyFrame_.size()) ? keyFrame_.at(index) : NULL; -#else - kf_[3] = keyFrame_.next(); -#endif - } - // Add last KeyFrame - path_.push_back(Frame(kf_[1]->position(), kf_[1]->orientation())); - } - pathIsValid_ = true; - } + if (keyFrame_.isEmpty()) + return; - if (mask) - { - glDisable(GL_LIGHTING); - glLineWidth(2); + if (!valuesAreValid_) + updateModifiedFrameValues(); - if (mask & 1) - { - glBegin(GL_LINE_STRIP); -#if QT_VERSION >= 0x040000 - Q_FOREACH (Frame fr, path_) - glVertex3fv(fr.position()); -#else -# if QT_VERSION < 0x030000 - for (int i=0; i < path_.size(); ++i) - glVertex3fv((path_.at(i)).position()); -# else - for (QValueVector::const_iterator pnt=path_.begin(), end=path_.end(); pnt!=end; ++pnt) - glVertex3fv((*pnt).position()); -# endif -#endif - glEnd(); + if (keyFrame_.first() == keyFrame_.last()) + path_.push_back(Frame(keyFrame_.first()->position(), keyFrame_.first()->orientation())); + else + { + static Frame fr; + KeyFrame* kf_[4]; + kf_[0] = keyFrame_.first(); + kf_[1] = kf_[0]; + int index = 1; + kf_[2] = (index < keyFrame_.size()) ? keyFrame_.at(index) : NULL; + index++; + kf_[3] = (index < keyFrame_.size()) ? keyFrame_.at(index) : NULL; + + while (kf_[2]) + { + Vec diff = kf_[2]->position() - kf_[1]->position(); + Vec v1 = 3.0 * diff - 2.0 * kf_[1]->tgP() - kf_[2]->tgP(); + Vec v2 = -2.0 * diff + kf_[1]->tgP() + kf_[2]->tgP(); + + // cout << kf_[0]->time() << " , " << kf_[1]->time() << " , " << kf_[2]->time() << " , " << kf_[3]->time() << endl; + for (int step=0; step(nbSteps); + fr.setPosition(kf_[1]->position() + alpha * (kf_[1]->tgP() + alpha * (v1+alpha*v2))); + fr.setOrientation(Quaternion::squad(kf_[1]->orientation(), kf_[1]->tgQ(), kf_[2]->tgQ(), kf_[2]->orientation(), alpha)); + path_.push_back(fr); + } + + // Shift + kf_[0] = kf_[1]; + kf_[1] = kf_[2]; + kf_[2] = kf_[3]; + index++; + kf_[3] = (index < keyFrame_.size()) ? keyFrame_.at(index) : NULL; + } + // Add last KeyFrame + path_.push_back(Frame(kf_[1]->position(), kf_[1]->orientation())); + } + pathIsValid_ = true; } - if (mask & 6) + + if (mask) { - int count = 0; - if (nbFrames > nbSteps) - nbFrames = nbSteps; - float goal = 0.0f; -#if QT_VERSION >= 0x040000 - Q_FOREACH (Frame fr, path_) -#else -# if QT_VERSION < 0x030000 - for (int i=0; i < path_.size(); ++i) -# else - for (QValueVector::const_iterator pnt=path_.begin(), end=path_.end(); pnt!=end; ++pnt) -# endif -#endif - if ((count++) >= goal) + glDisable(GL_LIGHTING); + glLineWidth(2); + + if (mask & 1) { - goal += nbSteps / static_cast(nbFrames); - glPushMatrix(); -#if QT_VERSION >= 0x040000 - glMultMatrixd(fr.matrix()); -#else -# if QT_VERSION < 0x030000 - glMultMatrixd((path_.at(i)).matrix()); -# else - glMultMatrixd((*pnt).matrix()); -# endif -#endif - if (mask & 2) drawCamera(scale); - if (mask & 4) QGLViewer::drawAxis(scale/10.0); - glPopMatrix(); + glBegin(GL_LINE_STRIP); + Q_FOREACH (Frame fr, path_) + glVertex3fv(fr.position()); + glEnd(); + } + if (mask & 6) + { + int count = 0; + if (nbFrames > nbSteps) + nbFrames = nbSteps; + qreal goal = 0.0; + Q_FOREACH (Frame fr, path_) + if ((count++) >= goal) + { + goal += nbSteps / static_cast(nbFrames); + glPushMatrix(); + glMultMatrixd(fr.matrix()); + if (mask & 2) drawCamera(scale); + if (mask & 4) QGLViewer::drawAxis(scale/10.0); + glPopMatrix(); + } } } - } } void KeyFrameInterpolator::updateModifiedFrameValues() { - Quaternion prevQ = keyFrame_.first()->orientation(); - KeyFrame* kf; -#if QT_VERSION >= 0x040000 - for (int i=0; iframe()) - kf->updateValuesFromPointer(); - kf->flipOrientationIfNeeded(prevQ); - prevQ = kf->orientation(); - } - - KeyFrame* prev = keyFrame_.first(); - kf = keyFrame_.first(); -#if QT_VERSION >= 0x040000 - int index = 1; -#endif - while (kf) - { -#if QT_VERSION >= 0x040000 - KeyFrame* next = (index < keyFrame_.size()) ? keyFrame_.at(index) : NULL; - index++; -#else - KeyFrame* next = keyFrame_.next(); -#endif - if (next) - kf->computeTangent(prev, next); - else - kf->computeTangent(prev, kf); - prev = kf; - kf = next; - } - valuesAreValid_ = true; + Quaternion prevQ = keyFrame_.first()->orientation(); + KeyFrame* kf; + for (int i=0; iframe()) + kf->updateValuesFromPointer(); + kf->flipOrientationIfNeeded(prevQ); + prevQ = kf->orientation(); + } + + KeyFrame* prev = keyFrame_.first(); + kf = keyFrame_.first(); + int index = 1; + while (kf) + { + KeyFrame* next = (index < keyFrame_.size()) ? keyFrame_.at(index) : NULL; + index++; + if (next) + kf->computeTangent(prev, next); + else + kf->computeTangent(prev, kf); + prev = kf; + kf = next; + } + valuesAreValid_ = true; } /*! Returns the Frame associated with the keyFrame at index \p index. @@ -521,141 +458,106 @@ void KeyFrameInterpolator::updateModifiedFrameValues() const)), the \e current pointed Frame state is returned. */ Frame KeyFrameInterpolator::keyFrame(int index) const { - const KeyFrame* const kf = keyFrame_.at(index); - return Frame(kf->position(), kf->orientation()); + const KeyFrame* const kf = keyFrame_.at(index); + return Frame(kf->position(), kf->orientation()); } /*! Returns the time corresponding to the \p index keyFrame. See also keyFrame(). \p index has to be in the range 0..numberOfKeyFrames()-1. */ -float KeyFrameInterpolator::keyFrameTime(int index) const +qreal KeyFrameInterpolator::keyFrameTime(int index) const { - return keyFrame_.at(index)->time(); + return keyFrame_.at(index)->time(); } /*! Returns the duration of the KeyFrameInterpolator path, expressed in seconds. Simply corresponds to lastTime() - firstTime(). Returns 0.0 if the path has less than 2 keyFrames. See also keyFrameTime(). */ -float KeyFrameInterpolator::duration() const +qreal KeyFrameInterpolator::duration() const { - return lastTime() - firstTime(); + return lastTime() - firstTime(); } /*! Returns the time corresponding to the first keyFrame, expressed in seconds. Returns 0.0 if the path is empty. See also lastTime(), duration() and keyFrameTime(). */ -float KeyFrameInterpolator::firstTime() const +qreal KeyFrameInterpolator::firstTime() const { - if (keyFrame_.isEmpty()) - return 0.0; - else - return keyFrame_.first()->time(); + if (keyFrame_.isEmpty()) + return 0.0; + else + return keyFrame_.first()->time(); } /*! Returns the time corresponding to the last keyFrame, expressed in seconds. Returns 0.0 if the path is empty. See also firstTime(), duration() and keyFrameTime(). */ -float KeyFrameInterpolator::lastTime() const +qreal KeyFrameInterpolator::lastTime() const { - if (keyFrame_.isEmpty()) - return 0.0; - else - return keyFrame_.last()->time(); + if (keyFrame_.isEmpty()) + return 0.0; + else + return keyFrame_.last()->time(); } -void KeyFrameInterpolator::updateCurrentKeyFrameForTime(float time) +void KeyFrameInterpolator::updateCurrentKeyFrameForTime(qreal time) { - // Assertion: times are sorted in monotone order. - // Assertion: keyFrame_ is not empty - - // TODO: Special case for loops when closed path is implemented !! - if (!currentFrameValid_) - // Recompute everything from scrach -#if QT_VERSION >= 0x040000 - currentFrame_[1]->toFront(); -#else - currentFrame_[1]->toFirst(); -#endif - - while (currentFrame_[1]->peekNext()->time() > time) - { - currentFrameValid_ = false; -#if QT_VERSION >= 0x040000 - if (!currentFrame_[1]->hasPrevious()) -#else - if (currentFrame_[1]->atFirst()) -#endif - break; -#if QT_VERSION >= 0x040000 - currentFrame_[1]->previous(); -#else - --(*currentFrame_[1]); -#endif - } - - if (!currentFrameValid_) - *currentFrame_[2] = *currentFrame_[1]; - - while (currentFrame_[2]->peekNext()->time() < time) - { - currentFrameValid_ = false; -#if QT_VERSION >= 0x040000 - if (!currentFrame_[2]->hasNext()) -#else - if (currentFrame_[2]->atLast()) -#endif - break; -#if QT_VERSION >= 0x040000 - currentFrame_[2]->next(); -#else - ++(*currentFrame_[2]); -#endif - } - - if (!currentFrameValid_) - { - *currentFrame_[1] = *currentFrame_[2]; -#if QT_VERSION >= 0x040000 - if ((currentFrame_[1]->hasPrevious()) && (time < currentFrame_[2]->peekNext()->time())) - currentFrame_[1]->previous(); -#else - if ((!currentFrame_[1]->atFirst()) && (time < currentFrame_[2]->current()->time())) - --(*currentFrame_[1]); -#endif - - *currentFrame_[0] = *currentFrame_[1]; -#if QT_VERSION >= 0x040000 - if (currentFrame_[0]->hasPrevious()) - currentFrame_[0]->previous(); -#else - if (!currentFrame_[0]->atFirst()) - --(*currentFrame_[0]); -#endif - - *currentFrame_[3] = *currentFrame_[2]; -#if QT_VERSION >= 0x040000 - if (currentFrame_[3]->hasNext()) - currentFrame_[3]->next(); -#else - if (!currentFrame_[3]->atLast()) - ++(*currentFrame_[3]); -#endif - - currentFrameValid_ = true; - splineCacheIsValid_ = false; - } - - // cout << "Time = " << time << " : " << currentFrame_[0]->peekNext()->time() << " , " << - // currentFrame_[1]->peekNext()->time() << " , " << currentFrame_[2]->peekNext()->time() << " , " << currentFrame_[3]->peekNext()->time() << endl; + // Assertion: times are sorted in monotone order. + // Assertion: keyFrame_ is not empty + + // TODO: Special case for loops when closed path is implemented !! + if (!currentFrameValid_) + // Recompute everything from scrach + currentFrame_[1]->toFront(); + + while (currentFrame_[1]->peekNext()->time() > time) + { + currentFrameValid_ = false; + if (!currentFrame_[1]->hasPrevious()) + break; + currentFrame_[1]->previous(); + } + + if (!currentFrameValid_) + *currentFrame_[2] = *currentFrame_[1]; + + while (currentFrame_[2]->peekNext()->time() < time) + { + currentFrameValid_ = false; + if (!currentFrame_[2]->hasNext()) + break; + currentFrame_[2]->next(); + } + + if (!currentFrameValid_) + { + *currentFrame_[1] = *currentFrame_[2]; + if ((currentFrame_[1]->hasPrevious()) && (time < currentFrame_[2]->peekNext()->time())) + currentFrame_[1]->previous(); + + *currentFrame_[0] = *currentFrame_[1]; + if (currentFrame_[0]->hasPrevious()) + currentFrame_[0]->previous(); + + *currentFrame_[3] = *currentFrame_[2]; + if (currentFrame_[3]->hasNext()) + currentFrame_[3]->next(); + + currentFrameValid_ = true; + splineCacheIsValid_ = false; + } + + // cout << "Time = " << time << " : " << currentFrame_[0]->peekNext()->time() << " , " << + // currentFrame_[1]->peekNext()->time() << " , " << currentFrame_[2]->peekNext()->time() << " , " << currentFrame_[3]->peekNext()->time() << endl; } void KeyFrameInterpolator::updateSplineCache() { - Vec delta = currentFrame_[2]->peekNext()->position() - currentFrame_[1]->peekNext()->position(); - v1 = 3.0 * delta - 2.0 * currentFrame_[1]->peekNext()->tgP() - currentFrame_[2]->peekNext()->tgP(); - v2 = -2.0 * delta + currentFrame_[1]->peekNext()->tgP() + currentFrame_[2]->peekNext()->tgP(); - splineCacheIsValid_ = true; + Vec delta = currentFrame_[2]->peekNext()->position() - currentFrame_[1]->peekNext()->position(); + v1 = 3.0 * delta - 2.0 * currentFrame_[1]->peekNext()->tgP() - currentFrame_[2]->peekNext()->tgP(); + v2 = -2.0 * delta + currentFrame_[1]->peekNext()->tgP() + currentFrame_[2]->peekNext()->tgP(); + splineCacheIsValid_ = true; } /*! Interpolate frame() at time \p time (expressed in seconds). interpolationTime() is set to \p @@ -665,36 +567,36 @@ void KeyFrameInterpolator::updateSplineCache() setInterpolationTime() instead. Emits the interpolated() signal and makes the frame() emit the Frame::interpolated() signal. */ -void KeyFrameInterpolator::interpolateAtTime(float time) +void KeyFrameInterpolator::interpolateAtTime(qreal time) { - setInterpolationTime(time); + setInterpolationTime(time); - if ((keyFrame_.isEmpty()) || (!frame())) - return; + if ((keyFrame_.isEmpty()) || (!frame())) + return; - if (!valuesAreValid_) - updateModifiedFrameValues(); + if (!valuesAreValid_) + updateModifiedFrameValues(); - updateCurrentKeyFrameForTime(time); + updateCurrentKeyFrameForTime(time); - if (!splineCacheIsValid_) - updateSplineCache(); + if (!splineCacheIsValid_) + updateSplineCache(); - float alpha; - float dt = currentFrame_[2]->peekNext()->time() - currentFrame_[1]->peekNext()->time(); - if (dt == 0.0) - alpha = 0.0; - else - alpha = (time - currentFrame_[1]->peekNext()->time()) / dt; + qreal alpha; + qreal dt = currentFrame_[2]->peekNext()->time() - currentFrame_[1]->peekNext()->time(); + if (dt == 0.0) + alpha = 0.0; + else + alpha = (time - currentFrame_[1]->peekNext()->time()) / dt; - // Linear interpolation - debug - // Vec pos = alpha*(currentFrame_[2]->peekNext()->position()) + (1.0-alpha)*(currentFrame_[1]->peekNext()->position()); - Vec pos = currentFrame_[1]->peekNext()->position() + alpha * (currentFrame_[1]->peekNext()->tgP() + alpha * (v1+alpha*v2)); - Quaternion q = Quaternion::squad(currentFrame_[1]->peekNext()->orientation(), currentFrame_[1]->peekNext()->tgQ(), - currentFrame_[2]->peekNext()->tgQ(), currentFrame_[2]->peekNext()->orientation(), alpha); - frame()->setPositionAndOrientationWithConstraint(pos, q); + // Linear interpolation - debug + // Vec pos = alpha*(currentFrame_[2]->peekNext()->position()) + (1.0-alpha)*(currentFrame_[1]->peekNext()->position()); + Vec pos = currentFrame_[1]->peekNext()->position() + alpha * (currentFrame_[1]->peekNext()->tgP() + alpha * (v1+alpha*v2)); + Quaternion q = Quaternion::squad(currentFrame_[1]->peekNext()->orientation(), currentFrame_[1]->peekNext()->tgQ(), + currentFrame_[2]->peekNext()->tgQ(), currentFrame_[2]->peekNext()->orientation(), alpha); + frame()->setPositionAndOrientationWithConstraint(pos, q); - Q_EMIT interpolated(); + Q_EMIT interpolated(); } /*! Returns an XML \c QDomElement that represents the KeyFrameInterpolator. @@ -714,28 +616,24 @@ void KeyFrameInterpolator::interpolateAtTime(float time) when a QGLViewer is closed. */ QDomElement KeyFrameInterpolator::domElement(const QString& name, QDomDocument& document) const { - QDomElement de = document.createElement(name); - int count = 0; -#if QT_VERSION >= 0x040000 - Q_FOREACH (KeyFrame* kf, keyFrame_) -#else - for (KeyFrame* kf = keyFrame_.first(); kf; kf = keyFrame_.next() ) -#endif - { - Frame fr(kf->position(), kf->orientation()); - QDomElement kfNode = fr.domElement("KeyFrame", document); - kfNode.setAttribute("index", QString::number(count)); - kfNode.setAttribute("time", QString::number(kf->time())); - de.appendChild(kfNode); - ++count; - } - de.setAttribute("nbKF", QString::number(keyFrame_.count())); - de.setAttribute("time", QString::number(interpolationTime())); - de.setAttribute("speed", QString::number(interpolationSpeed())); - de.setAttribute("period", QString::number(interpolationPeriod())); - de.setAttribute("closedPath", (closedPath()?"true":"false")); - de.setAttribute("loop", (loopInterpolation()?"true":"false")); - return de; + QDomElement de = document.createElement(name); + int count = 0; + Q_FOREACH (KeyFrame* kf, keyFrame_) + { + Frame fr(kf->position(), kf->orientation()); + QDomElement kfNode = fr.domElement("KeyFrame", document); + kfNode.setAttribute("index", QString::number(count)); + kfNode.setAttribute("time", QString::number(kf->time())); + de.appendChild(kfNode); + ++count; + } + de.setAttribute("nbKF", QString::number(keyFrame_.count())); + de.setAttribute("time", QString::number(interpolationTime())); + de.setAttribute("speed", QString::number(interpolationSpeed())); + de.setAttribute("period", QString::number(interpolationPeriod())); + DomUtils::setBoolAttribute(de, "closedPath", closedPath()); + DomUtils::setBoolAttribute(de, "loop", loopInterpolation()); + return de; } /*! Restores the KeyFrameInterpolator state from a \c QDomElement created by domElement(). @@ -748,71 +646,69 @@ QDomElement KeyFrameInterpolator::domElement(const QString& name, QDomDocument& See also Camera::initFromDOMElement() and Frame::initFromDOMElement(). */ void KeyFrameInterpolator::initFromDOMElement(const QDomElement& element) { -#if QT_VERSION >= 0x040000 - qDeleteAll(keyFrame_); -#endif - keyFrame_.clear(); - QDomElement child=element.firstChild().toElement(); - while (!child.isNull()) - { - if (child.tagName() == "KeyFrame") + qDeleteAll(keyFrame_); + keyFrame_.clear(); + QDomElement child=element.firstChild().toElement(); + while (!child.isNull()) { - Frame fr; - fr.initFromDOMElement(child); - float time = DomUtils::floatFromDom(child, "time", 0.0); - addKeyFrame(fr, time); - } + if (child.tagName() == "KeyFrame") + { + Frame fr; + fr.initFromDOMElement(child); + qreal time = DomUtils::qrealFromDom(child, "time", 0.0); + addKeyFrame(fr, time); + } - child = child.nextSibling().toElement(); - } + child = child.nextSibling().toElement(); + } - // #CONNECTION# Values cut pasted from constructor - setInterpolationTime(DomUtils::floatFromDom(element, "time", 0.0)); - setInterpolationSpeed(DomUtils::floatFromDom(element, "speed", 1.0)); - setInterpolationPeriod(DomUtils::intFromDom(element, "period", 40)); - setClosedPath(DomUtils::boolFromDom(element, "closedPath", false)); - setLoopInterpolation(DomUtils::boolFromDom(element, "loop", false)); + // #CONNECTION# Values cut pasted from constructor + setInterpolationTime(DomUtils::qrealFromDom(element, "time", 0.0)); + setInterpolationSpeed(DomUtils::qrealFromDom(element, "speed", 1.0)); + setInterpolationPeriod(DomUtils::intFromDom(element, "period", 40)); + setClosedPath(DomUtils::boolFromDom(element, "closedPath", false)); + setLoopInterpolation(DomUtils::boolFromDom(element, "loop", false)); - // setFrame(NULL); - pathIsValid_ = false; - valuesAreValid_ = false; - currentFrameValid_ = false; + // setFrame(NULL); + pathIsValid_ = false; + valuesAreValid_ = false; + currentFrameValid_ = false; - stopInterpolation(); + stopInterpolation(); } #ifndef DOXYGEN //////////// KeyFrame private class implementation ///////// -KeyFrameInterpolator::KeyFrame::KeyFrame(const Frame& fr, float t) - : time_(t), frame_(NULL) +KeyFrameInterpolator::KeyFrame::KeyFrame(const Frame& fr, qreal t) + : time_(t), frame_(NULL) { - p_ = fr.position(); - q_ = fr.orientation(); + p_ = fr.position(); + q_ = fr.orientation(); } -KeyFrameInterpolator::KeyFrame::KeyFrame(const Frame* fr, float t) - : time_(t), frame_(fr) +KeyFrameInterpolator::KeyFrame::KeyFrame(const Frame* fr, qreal t) + : time_(t), frame_(fr) { - updateValuesFromPointer(); + updateValuesFromPointer(); } void KeyFrameInterpolator::KeyFrame::updateValuesFromPointer() { - p_ = frame()->position(); - q_ = frame()->orientation(); + p_ = frame()->position(); + q_ = frame()->orientation(); } void KeyFrameInterpolator::KeyFrame::computeTangent(const KeyFrame* const prev, const KeyFrame* const next) { - tgP_ = 0.5 * (next->position() - prev->position()); - tgQ_ = Quaternion::squadTangent(prev->orientation(), q_, next->orientation()); + tgP_ = 0.5 * (next->position() - prev->position()); + tgQ_ = Quaternion::squadTangent(prev->orientation(), q_, next->orientation()); } void KeyFrameInterpolator::KeyFrame::flipOrientationIfNeeded(const Quaternion& prev) { - if (Quaternion::dot(prev, q_) < 0.0) - q_.negate(); + if (Quaternion::dot(prev, q_) < 0.0) + q_.negate(); } #endif //DOXYGEN diff --git a/octovis/src/extern/QGLViewer/keyFrameInterpolator.h b/octovis/src/extern/QGLViewer/keyFrameInterpolator.h index 11daeb82..100cd2f1 100644 --- a/octovis/src/extern/QGLViewer/keyFrameInterpolator.h +++ b/octovis/src/extern/QGLViewer/keyFrameInterpolator.h @@ -1,8 +1,8 @@ /**************************************************************************** - Copyright (C) 2002-2013 Gilles Debunne. All rights reserved. + Copyright (C) 2002-2014 Gilles Debunne. All rights reserved. - This file is part of the QGLViewer library version 2.4.0. + This file is part of the QGLViewer library version 2.6.3. http://www.libqglviewer.com - contact@libqglviewer.com @@ -23,13 +23,8 @@ #ifndef QGLVIEWER_KEY_FRAME_INTERPOLATOR_H #define QGLVIEWER_KEY_FRAME_INTERPOLATOR_H -#if QT_VERSION > 0x040000 -# include -# include -#else -# include -# include -#endif +#include +#include #include "quaternion.h" // Not actually needed, but some bad compilers (Microsoft VS6) complain. @@ -40,9 +35,9 @@ // and comment "class Frame;" 3 lines below namespace qglviewer { - class Camera; - class Frame; - /*! \brief A keyFrame Catmull-Rom Frame interpolator. +class Camera; +class Frame; +/*! \brief A keyFrame Catmull-Rom Frame interpolator. \class KeyFrameInterpolator keyFrameInterpolator.h QGLViewer/keyFrameInterpolator.h A KeyFrameInterpolator holds keyFrames (that define a path) and a pointer to a Frame of your @@ -56,24 +51,24 @@ namespace qglviewer { init() { - // The KeyFrameInterpolator kfi is given the Frame that it will drive over time. - kfi = new KeyFrameInterpolator( new Frame() ); - kfi->addKeyFrame( Frame( Vec(1,0,0), Quaternion() ) ); - kfi->addKeyFrame( new Frame( Vec(2,1,0), Quaternion() ) ); - // ...and so on for all the keyFrames. + // The KeyFrameInterpolator kfi is given the Frame that it will drive over time. + kfi = new KeyFrameInterpolator( new Frame() ); + kfi->addKeyFrame( Frame( Vec(1,0,0), Quaternion() ) ); + kfi->addKeyFrame( new Frame( Vec(2,1,0), Quaternion() ) ); + // ...and so on for all the keyFrames. - // Ask for a display update after each update of the KeyFrameInterpolator - connect(kfi, SIGNAL(interpolated()), SLOT(updateGL())); + // Ask for a display update after each update of the KeyFrameInterpolator + connect(kfi, SIGNAL(interpolated()), SLOT(update())); - kfi->startInterpolation(); + kfi->startInterpolation(); } draw() { - glPushMatrix(); - glMultMatrixd( kfi->frame()->matrix() ); - // Draw your object here. Its position and orientation are interpolated. - glPopMatrix(); + glPushMatrix(); + glMultMatrixd( kfi->frame()->matrix() ); + // Draw your object here. Its position and orientation are interpolated. + glPopMatrix(); } \endcode @@ -98,7 +93,7 @@ namespace qglviewer { especially useful for benchmarking or movie creation (constant number of snapshots). During the interpolation, the KeyFrameInterpolator emits an interpolated() signal, which will - usually be connected to the QGLViewer::updateGL() slot. The interpolation is stopped when + usually be connected to the QGLViewer::update() slot. The interpolation is stopped when interpolationTime() is greater than the lastTime() (unless loopInterpolation() is \c true) and the endReached() signal is then emitted. @@ -119,255 +114,243 @@ namespace qglviewer { KeyFrameInterpolator kfi( new Frame() ); // calls to kfi.addKeyFrame() to define the path. - const float deltaTime = 0.04; // output a position every deltaTime seconds - for (float time=kfi.firstTime(); time<=kfi.lastTime(); time += deltaTime) + const qreal deltaTime = 0.04; // output a position every deltaTime seconds + for (qreal time=kfi.firstTime(); time<=kfi.lastTime(); time += deltaTime) { - kfi.interpolateAtTime(time); - cout << "t=" << time << "\tpos=" << kfi.frame()->position() << endl; + kfi.interpolateAtTime(time); + cout << "t=" << time << "\tpos=" << kfi.frame()->position() << endl; } \endcode You may want to temporally disconnect the \c kfi interpolated() signal from the - QGLViewer::updateGL() slot before calling this code. \nosubgrouping */ - class QGLVIEWER_EXPORT KeyFrameInterpolator : public QObject - { - // todo closedPath, insertKeyFrames, deleteKeyFrame, replaceKeyFrame - Q_OBJECT - - public: - KeyFrameInterpolator(Frame* fr=NULL); - virtual ~KeyFrameInterpolator(); - - Q_SIGNALS: - /*! This signal is emitted whenever the frame() state is interpolated. - - The emission of this signal triggers the synchronous emission of the frame() - Frame::interpolated() signal, which may also be useful. - - This signal should especially be connected to your QGLViewer::updateGL() slot, so that the display - is updated after every update of the KeyFrameInterpolator frame(): - \code - connect(myKeyFrameInterpolator, SIGNAL(interpolated()), SLOT(updateGL())); - \endcode - Use the QGLViewer::QGLViewerPool() to connect the signal to all the viewers. - - Note that the QGLViewer::camera() Camera::keyFrameInterpolator() created using QGLViewer::pathKey() - have their interpolated() signals automatically connected to the QGLViewer::updateGL() slot. */ - void interpolated(); - - /*! This signal is emitted when the interpolation reaches the first (when interpolationSpeed() - is negative) or the last keyFrame. - - When loopInterpolation() is \c true, interpolationTime() is reset and the interpolation - continues. It otherwise stops. */ - void endReached(); - - /*! @name Path creation */ - //@{ - public Q_SLOTS: - void addKeyFrame(const Frame& frame); - void addKeyFrame(const Frame& frame, float time); - - void addKeyFrame(const Frame* const frame); - void addKeyFrame(const Frame* const frame, float time); - - void deletePath(); - //@} - - /*! @name Associated Frame */ - //@{ - public: - /*! Returns the associated Frame and that is interpolated by the KeyFrameInterpolator. - - When interpolationIsStarted(), this Frame's position and orientation will regularly be updated - by a timer, so that they follow the KeyFrameInterpolator path. - - Set using setFrame() or with the KeyFrameInterpolator constructor. */ - Frame* frame() const { return frame_; }; - - public Q_SLOTS: - void setFrame(Frame* const frame); - //@} - - /*! @name Path parameters */ - //@{ - public: - Frame keyFrame(int index) const; - float keyFrameTime(int index) const; - /*! Returns the number of keyFrames used by the interpolation. Use addKeyFrame() to add new keyFrames. */ - int numberOfKeyFrames() const { return keyFrame_.count(); }; - float duration() const; - float firstTime() const; - float lastTime() const; - //@} - - /*! @name Interpolation parameters */ - //@{ - public: - /*! Returns the current interpolation time (in seconds) along the KeyFrameInterpolator path. - - This time is regularly updated when interpolationIsStarted(). Can be set directly with - setInterpolationTime() or interpolateAtTime(). */ - float interpolationTime() const { return interpolationTime_; }; - /*! Returns the current interpolation speed. - - Default value is 1.0, which means keyFrameTime() will be matched during the interpolation - (provided that your main loop is fast enough). - - A negative value will result in a reverse interpolation of the keyFrames. See also - interpolationPeriod(). */ - float interpolationSpeed() const { return interpolationSpeed_; }; - /*! Returns the current interpolation period, expressed in milliseconds. - - The update of the frame() state will be done by a timer at this period when - interpolationIsStarted(). - - This period (multiplied by interpolationSpeed()) is added to the interpolationTime() at each - update, and the frame() state is modified accordingly (see interpolateAtTime()). Default value - is 40 milliseconds. */ - int interpolationPeriod() const { return period_; }; - /*! Returns \c true when the interpolation is played in an infinite loop. - - When \c false (default), the interpolation stops when interpolationTime() reaches firstTime() - (with negative interpolationSpeed()) or lastTime(). - - interpolationTime() is otherwise reset to firstTime() (+ interpolationTime() - lastTime()) (and - inversely for negative interpolationSpeed()) and interpolation continues. - - In both cases, the endReached() signal is emitted. */ - bool loopInterpolation() const { return loopInterpolation_; }; + QGLViewer::update() slot before calling this code. \nosubgrouping */ +class QGLVIEWER_EXPORT KeyFrameInterpolator : public QObject +{ + // todo closedPath, insertKeyFrames, deleteKeyFrame, replaceKeyFrame + Q_OBJECT + +public: + KeyFrameInterpolator(Frame* fr=NULL); + virtual ~KeyFrameInterpolator(); + +Q_SIGNALS: + /*! This signal is emitted whenever the frame() state is interpolated. + + The emission of this signal triggers the synchronous emission of the frame() + Frame::interpolated() signal, which may also be useful. + + This signal should especially be connected to your QGLViewer::update() slot, so that the display + is updated after every update of the KeyFrameInterpolator frame(): + \code + connect(myKeyFrameInterpolator, SIGNAL(interpolated()), SLOT(update())); + \endcode + Use the QGLViewer::QGLViewerPool() to connect the signal to all the viewers. + + Note that the QGLViewer::camera() Camera::keyFrameInterpolator() created using QGLViewer::pathKey() + have their interpolated() signals automatically connected to the QGLViewer::update() slot. */ + void interpolated(); + + /*! This signal is emitted when the interpolation reaches the first (when interpolationSpeed() + is negative) or the last keyFrame. + + When loopInterpolation() is \c true, interpolationTime() is reset and the interpolation + continues. It otherwise stops. */ + void endReached(); + + /*! @name Path creation */ + //@{ +public Q_SLOTS: + void addKeyFrame(const Frame& frame); + void addKeyFrame(const Frame& frame, qreal time); + + void addKeyFrame(const Frame* const frame); + void addKeyFrame(const Frame* const frame, qreal time); + + void deletePath(); + //@} + + /*! @name Associated Frame */ + //@{ +public: + /*! Returns the associated Frame and that is interpolated by the KeyFrameInterpolator. + + When interpolationIsStarted(), this Frame's position and orientation will regularly be updated + by a timer, so that they follow the KeyFrameInterpolator path. + + Set using setFrame() or with the KeyFrameInterpolator constructor. */ + Frame* frame() const { return frame_; } + +public Q_SLOTS: + void setFrame(Frame* const frame); + //@} + + /*! @name Path parameters */ + //@{ +public: + Frame keyFrame(int index) const; + qreal keyFrameTime(int index) const; + /*! Returns the number of keyFrames used by the interpolation. Use addKeyFrame() to add new keyFrames. */ + int numberOfKeyFrames() const { return keyFrame_.count(); } + qreal duration() const; + qreal firstTime() const; + qreal lastTime() const; + //@} + + /*! @name Interpolation parameters */ + //@{ +public: + /*! Returns the current interpolation time (in seconds) along the KeyFrameInterpolator path. + + This time is regularly updated when interpolationIsStarted(). Can be set directly with + setInterpolationTime() or interpolateAtTime(). */ + qreal interpolationTime() const { return interpolationTime_; } + /*! Returns the current interpolation speed. + + Default value is 1.0, which means keyFrameTime() will be matched during the interpolation + (provided that your main loop is fast enough). + + A negative value will result in a reverse interpolation of the keyFrames. See also + interpolationPeriod(). */ + qreal interpolationSpeed() const { return interpolationSpeed_; } + /*! Returns the current interpolation period, expressed in milliseconds. + + The update of the frame() state will be done by a timer at this period when + interpolationIsStarted(). + + This period (multiplied by interpolationSpeed()) is added to the interpolationTime() at each + update, and the frame() state is modified accordingly (see interpolateAtTime()). Default value + is 40 milliseconds. */ + int interpolationPeriod() const { return period_; } + /*! Returns \c true when the interpolation is played in an infinite loop. + + When \c false (default), the interpolation stops when interpolationTime() reaches firstTime() + (with negative interpolationSpeed()) or lastTime(). + + interpolationTime() is otherwise reset to firstTime() (+ interpolationTime() - lastTime()) (and + inversely for negative interpolationSpeed()) and interpolation continues. + + In both cases, the endReached() signal is emitted. */ + bool loopInterpolation() const { return loopInterpolation_; } #ifndef DOXYGEN - /*! Whether or not (default) the path defined by the keyFrames is a closed loop. When \c true, - the last and the first KeyFrame are linked by a new spline segment. + /*! Whether or not (default) the path defined by the keyFrames is a closed loop. When \c true, + the last and the first KeyFrame are linked by a new spline segment. - Use setLoopInterpolation() to create a continuous animation over the entire path. - \attention The closed path feature is not yet implemented. */ - bool closedPath() const { return closedPath_; }; + Use setLoopInterpolation() to create a continuous animation over the entire path. + \attention The closed path feature is not yet implemented. */ + bool closedPath() const { return closedPath_; } #endif - public Q_SLOTS: - /*! Sets the interpolationTime(). - - \attention The frame() state is not affected by this method. Use this function to define the - starting time of a future interpolation (see startInterpolation()). Use interpolateAtTime() to - actually interpolate at a given time. */ - void setInterpolationTime(float time) { interpolationTime_ = time; }; - /*! Sets the interpolationSpeed(). Negative or null values are allowed. */ - void setInterpolationSpeed(float speed) { interpolationSpeed_ = speed; }; - /*! Sets the interpolationPeriod(). */ - void setInterpolationPeriod(int period) { period_ = period; }; - /*! Sets the loopInterpolation() value. */ - void setLoopInterpolation(bool loop=true) { loopInterpolation_ = loop; }; +public Q_SLOTS: + /*! Sets the interpolationTime(). + + \attention The frame() state is not affected by this method. Use this function to define the + starting time of a future interpolation (see startInterpolation()). Use interpolateAtTime() to + actually interpolate at a given time. */ + void setInterpolationTime(qreal time) { interpolationTime_ = time; } + /*! Sets the interpolationSpeed(). Negative or null values are allowed. */ + void setInterpolationSpeed(qreal speed) { interpolationSpeed_ = speed; } + /*! Sets the interpolationPeriod(). */ + void setInterpolationPeriod(int period) { period_ = period; } + /*! Sets the loopInterpolation() value. */ + void setLoopInterpolation(bool loop=true) { loopInterpolation_ = loop; } #ifndef DOXYGEN - /*! Sets the closedPath() value. \attention The closed path feature is not yet implemented. */ - void setClosedPath(bool closed=true) { closedPath_ = closed; }; + /*! Sets the closedPath() value. \attention The closed path feature is not yet implemented. */ + void setClosedPath(bool closed=true) { closedPath_ = closed; } #endif - //@} - - - /*! @name Interpolation */ - //@{ - public: - /*! Returns \c true when the interpolation is being performed. Use startInterpolation(), - stopInterpolation() or toggleInterpolation() to modify this state. */ - bool interpolationIsStarted() const { return interpolationStarted_; }; - public Q_SLOTS: - void startInterpolation(int period = -1); - void stopInterpolation(); - void resetInterpolation(); - /*! Calls startInterpolation() or stopInterpolation(), depending on interpolationIsStarted(). */ - void toggleInterpolation() { if (interpolationIsStarted()) stopInterpolation(); else startInterpolation(); }; - virtual void interpolateAtTime(float time); - //@} - - /*! @name Path drawing */ - //@{ - public: - virtual void drawPath(int mask=1, int nbFrames=6, float scale=1.0f); - //@} - - /*! @name XML representation */ - //@{ - public: - virtual QDomElement domElement(const QString& name, QDomDocument& document) const; - virtual void initFromDOMElement(const QDomElement& element); - //@} - - private Q_SLOTS: - virtual void update(); - virtual void invalidateValues() { valuesAreValid_ = false; pathIsValid_ = false; splineCacheIsValid_ = false; }; - - private: - // Copy constructor and opertor= are declared private and undefined - // Prevents everyone from trying to use them - // KeyFrameInterpolator(const KeyFrameInterpolator& kfi); - // KeyFrameInterpolator& operator=(const KeyFrameInterpolator& kfi); - - void updateCurrentKeyFrameForTime(float time); - void updateModifiedFrameValues(); - void updateSplineCache(); + //@} + + + /*! @name Interpolation */ + //@{ +public: + /*! Returns \c true when the interpolation is being performed. Use startInterpolation(), + stopInterpolation() or toggleInterpolation() to modify this state. */ + bool interpolationIsStarted() const { return interpolationStarted_; } +public Q_SLOTS: + void startInterpolation(int period = -1); + void stopInterpolation(); + void resetInterpolation(); + /*! Calls startInterpolation() or stopInterpolation(), depending on interpolationIsStarted(). */ + void toggleInterpolation() { if (interpolationIsStarted()) stopInterpolation(); else startInterpolation(); } + virtual void interpolateAtTime(qreal time); + //@} + + /*! @name Path drawing */ + //@{ +public: + virtual void drawPath(int mask=1, int nbFrames=6, qreal scale=1.0); + //@} + + /*! @name XML representation */ + //@{ +public: + virtual QDomElement domElement(const QString& name, QDomDocument& document) const; + virtual void initFromDOMElement(const QDomElement& element); + //@} + +private Q_SLOTS: + virtual void update(); + virtual void invalidateValues() { valuesAreValid_ = false; pathIsValid_ = false; splineCacheIsValid_ = false; } + +private: + // Copy constructor and opertor= are declared private and undefined + // Prevents everyone from trying to use them + // KeyFrameInterpolator(const KeyFrameInterpolator& kfi); + // KeyFrameInterpolator& operator=(const KeyFrameInterpolator& kfi); + + void updateCurrentKeyFrameForTime(qreal time); + void updateModifiedFrameValues(); + void updateSplineCache(); #ifndef DOXYGEN - // Internal private KeyFrame representation - class KeyFrame - { - public: - KeyFrame(const Frame& fr, float t); - KeyFrame(const Frame* fr, float t); - - Vec position() const { return p_; } - Quaternion orientation() const { return q_; } - Vec tgP() const { return tgP_; } - Quaternion tgQ() const { return tgQ_; } - float time() const { return time_; } - const Frame* frame() const { return frame_; } - void updateValuesFromPointer(); - void flipOrientationIfNeeded(const Quaternion& prev); - void computeTangent(const KeyFrame* const prev, const KeyFrame* const next); - private: - Vec p_, tgP_; - Quaternion q_, tgQ_; - float time_; - const Frame* const frame_; - }; -#endif - - // K e y F r a m e s -#if QT_VERSION >= 0x040000 - mutable QList keyFrame_; - QMutableListIterator* currentFrame_[4]; - QList path_; -#else - mutable QPtrList keyFrame_; - // 4 succesive frames. interpolationTime_ is between index 1 and 2. - QPtrListIterator* currentFrame_[4]; -# if QT_VERSION >= 0x030000 - // Cached path computed values (for drawPath()). - QValueVector path_; -# else - QVector path_; -# endif + // Internal private KeyFrame representation + class KeyFrame + { + public: + KeyFrame(const Frame& fr, qreal t); + KeyFrame(const Frame* fr, qreal t); + + Vec position() const { return p_; } + Quaternion orientation() const { return q_; } + Vec tgP() const { return tgP_; } + Quaternion tgQ() const { return tgQ_; } + qreal time() const { return time_; } + const Frame* frame() const { return frame_; } + void updateValuesFromPointer(); + void flipOrientationIfNeeded(const Quaternion& prev); + void computeTangent(const KeyFrame* const prev, const KeyFrame* const next); + private: + Vec p_, tgP_; + Quaternion q_, tgQ_; + qreal time_; + const Frame* const frame_; + }; #endif - // A s s o c i a t e d f r a m e - Frame* frame_; - - // R h y t h m - QTimer timer_; - int period_; - float interpolationTime_; - float interpolationSpeed_; - bool interpolationStarted_; - - // M i s c - bool closedPath_; - bool loopInterpolation_; - - // C a c h e d v a l u e s a n d f l a g s - bool pathIsValid_; - bool valuesAreValid_; - bool currentFrameValid_; - bool splineCacheIsValid_; - Vec v1, v2; - }; + // K e y F r a m e s + mutable QList keyFrame_; + QMutableListIterator* currentFrame_[4]; + QList path_; + + // A s s o c i a t e d f r a m e + Frame* frame_; + + // R h y t h m + QTimer timer_; + int period_; + qreal interpolationTime_; + qreal interpolationSpeed_; + bool interpolationStarted_; + + // M i s c + bool closedPath_; + bool loopInterpolation_; + + // C a c h e d v a l u e s a n d f l a g s + bool pathIsValid_; + bool valuesAreValid_; + bool currentFrameValid_; + bool splineCacheIsValid_; + Vec v1, v2; +}; } // namespace qglviewer diff --git a/octovis/src/extern/QGLViewer/manipulatedCameraFrame.cpp b/octovis/src/extern/QGLViewer/manipulatedCameraFrame.cpp index 0eda0b6e..723b0f77 100644 --- a/octovis/src/extern/QGLViewer/manipulatedCameraFrame.cpp +++ b/octovis/src/extern/QGLViewer/manipulatedCameraFrame.cpp @@ -1,8 +1,8 @@ /**************************************************************************** - Copyright (C) 2002-2013 Gilles Debunne. All rights reserved. + Copyright (C) 2002-2014 Gilles Debunne. All rights reserved. - This file is part of the QGLViewer library version 2.4.0. + This file is part of the QGLViewer library version 2.6.3. http://www.libqglviewer.com - contact@libqglviewer.com @@ -24,55 +24,54 @@ #include "manipulatedCameraFrame.h" #include "qglviewer.h" -#if QT_VERSION >= 0x040000 -# include -#endif +#include using namespace qglviewer; using namespace std; /*! Default constructor. - flySpeed() is set to 0.0 and flyUpVector() is (0,1,0). The revolveAroundPoint() is set to (0,0,0). + flySpeed() is set to 0.0 and sceneUpVector() is (0,1,0). The pivotPoint() is set to (0,0,0). \attention Created object is removeFromMouseGrabberPool(). */ ManipulatedCameraFrame::ManipulatedCameraFrame() - : driveSpeed_(0.0), flyUpVector_(0.0, 1.0, 0.0) + : driveSpeed_(0.0), sceneUpVector_(0.0, 1.0, 0.0), rotatesAroundUpVector_(false), zoomsOnPivotPoint_(false) { - setFlySpeed(0.0); - removeFromMouseGrabberPool(); - - connect(&flyTimer_, SIGNAL(timeout()), SLOT(flyUpdate())); + setFlySpeed(0.0); + removeFromMouseGrabberPool(); + connect(&flyTimer_, SIGNAL(timeout()), SLOT(flyUpdate())); } /*! Equal operator. Calls ManipulatedFrame::operator=() and then copy attributes. */ ManipulatedCameraFrame& ManipulatedCameraFrame::operator=(const ManipulatedCameraFrame& mcf) { - ManipulatedFrame::operator=(mcf); + ManipulatedFrame::operator=(mcf); - setFlySpeed(mcf.flySpeed()); - setFlyUpVector(mcf.flyUpVector()); + setFlySpeed(mcf.flySpeed()); + setSceneUpVector(mcf.sceneUpVector()); + setRotatesAroundUpVector(mcf.rotatesAroundUpVector_); + setZoomsOnPivotPoint(mcf.zoomsOnPivotPoint_); - return *this; + return *this; } /*! Copy constructor. Performs a deep copy of all members using operator=(). */ ManipulatedCameraFrame::ManipulatedCameraFrame(const ManipulatedCameraFrame& mcf) - : ManipulatedFrame(mcf) + : ManipulatedFrame(mcf) { - removeFromMouseGrabberPool(); - connect(&flyTimer_, SIGNAL(timeout()), SLOT(flyUpdate())); - (*this)=(mcf); + removeFromMouseGrabberPool(); + connect(&flyTimer_, SIGNAL(timeout()), SLOT(flyUpdate())); + (*this)=(mcf); } //////////////////////////////////////////////////////////////////////////////// /*! Overloading of ManipulatedFrame::spin(). -Rotates the ManipulatedCameraFrame around its revolveAroundPoint() instead of its origin. */ +Rotates the ManipulatedCameraFrame around its pivotPoint() instead of its origin. */ void ManipulatedCameraFrame::spin() { - rotateAroundPoint(spinningQuaternion(), revolveAroundPoint()); + rotateAroundPoint(spinningQuaternion(), pivotPoint()); } #ifndef DOXYGEN @@ -80,36 +79,47 @@ void ManipulatedCameraFrame::spin() manipulated(). */ void ManipulatedCameraFrame::flyUpdate() { - static Vec flyDisp(0.0, 0.0, 0.0); - switch (action_) - { - case QGLViewer::MOVE_FORWARD: - flyDisp.z = -flySpeed(); - translate(localInverseTransformOf(flyDisp)); - break; - case QGLViewer::MOVE_BACKWARD: - flyDisp.z = flySpeed(); - translate(localInverseTransformOf(flyDisp)); - break; - case QGLViewer::DRIVE: - flyDisp.z = flySpeed() * driveSpeed_; - translate(localInverseTransformOf(flyDisp)); - break; - default: - break; - } - - // Needs to be out of the switch since ZOOM/fastDraw()/wheelEvent use this callback to trigger a final draw(). - // #CONNECTION# wheelEvent. - Q_EMIT manipulated(); + static Vec flyDisp(0.0, 0.0, 0.0); + switch (action_) + { + case QGLViewer::MOVE_FORWARD: + flyDisp.z = -flySpeed(); + translate(localInverseTransformOf(flyDisp)); + break; + case QGLViewer::MOVE_BACKWARD: + flyDisp.z = flySpeed(); + translate(localInverseTransformOf(flyDisp)); + break; + case QGLViewer::DRIVE: + flyDisp.z = flySpeed() * driveSpeed_; + translate(localInverseTransformOf(flyDisp)); + break; + default: + break; + } + + // Needs to be out of the switch since ZOOM/fastDraw()/wheelEvent use this callback to trigger a final draw(). + // #CONNECTION# wheelEvent. + Q_EMIT manipulated(); +} + +Vec ManipulatedCameraFrame::flyUpVector() const { + qWarning("flyUpVector() is deprecated. Use sceneUpVector() instead."); + return sceneUpVector(); +} + +void ManipulatedCameraFrame::setFlyUpVector(const Vec& up) { + qWarning("setFlyUpVector() is deprecated. Use setSceneUpVector() instead."); + setSceneUpVector(up); } + #endif /*! This method will be called by the Camera when its orientation is changed, so that the -flyUpVector (private) is changed accordingly. You should not need to call this method. */ -void ManipulatedCameraFrame::updateFlyUpVector() +sceneUpVector (private) is changed accordingly. You should not need to call this method. */ +void ManipulatedCameraFrame::updateSceneUpVector() { - flyUpVector_ = inverseTransformOf(Vec(0.0, 1.0, 0.0)); + sceneUpVector_ = inverseTransformOf(Vec(0.0, 1.0, 0.0)); } //////////////////////////////////////////////////////////////////////////////// @@ -131,12 +141,14 @@ void ManipulatedCameraFrame::updateFlyUpVector() Frame::domElement(), Camera::domElement()... */ QDomElement ManipulatedCameraFrame::domElement(const QString& name, QDomDocument& document) const { - QDomElement e = ManipulatedFrame::domElement(name, document); - QDomElement mcp = document.createElement("ManipulatedCameraParameters"); - mcp.setAttribute("flySpeed", QString::number(flySpeed())); - mcp.appendChild(flyUpVector().domElement("flyUpVector", document)); - e.appendChild(mcp); - return e; + QDomElement e = ManipulatedFrame::domElement(name, document); + QDomElement mcp = document.createElement("ManipulatedCameraParameters"); + mcp.setAttribute("flySpeed", QString::number(flySpeed())); + DomUtils::setBoolAttribute(mcp, "rotatesAroundUpVector", rotatesAroundUpVector()); + DomUtils::setBoolAttribute(mcp, "zoomsOnPivotPoint", zoomsOnPivotPoint()); + mcp.appendChild(sceneUpVector().domElement("sceneUpVector", document)); + e.appendChild(mcp); + return e; } /*! Restores the ManipulatedCameraFrame state from a \c QDomElement created by domElement(). @@ -145,29 +157,31 @@ First calls ManipulatedFrame::initFromDOMElement() and then initializes Manipula specific parameters. */ void ManipulatedCameraFrame::initFromDOMElement(const QDomElement& element) { - // No need to initialize, since default flyUpVector and flySpeed are not meaningful. - // It's better to keep current ones. And it would destroy constraint() and referenceFrame(). - // *this = ManipulatedCameraFrame(); - ManipulatedFrame::initFromDOMElement(element); - - QDomElement child=element.firstChild().toElement(); - while (!child.isNull()) - { - if (child.tagName() == "ManipulatedCameraParameters") - { - setFlySpeed(DomUtils::floatFromDom(child, "flySpeed", flySpeed())); + // No need to initialize, since default sceneUpVector and flySpeed are not meaningful. + // It's better to keep current ones. And it would destroy constraint() and referenceFrame(). + // *this = ManipulatedCameraFrame(); + ManipulatedFrame::initFromDOMElement(element); - QDomElement schild=child.firstChild().toElement(); - while (!schild.isNull()) - { - if (schild.tagName() == "flyUpVector") - setFlyUpVector(Vec(schild)); - - schild = schild.nextSibling().toElement(); - } + QDomElement child=element.firstChild().toElement(); + while (!child.isNull()) + { + if (child.tagName() == "ManipulatedCameraParameters") + { + setFlySpeed(DomUtils::qrealFromDom(child, "flySpeed", flySpeed())); + setRotatesAroundUpVector(DomUtils::boolFromDom(child, "rotatesAroundUpVector", false)); + setZoomsOnPivotPoint(DomUtils::boolFromDom(child, "zoomsOnPivotPoint", false)); + + QDomElement schild=child.firstChild().toElement(); + while (!schild.isNull()) + { + if (schild.tagName() == "sceneUpVector") + setSceneUpVector(Vec(schild)); + + schild = schild.nextSibling().toElement(); + } + } + child = child.nextSibling().toElement(); } - child = child.nextSibling().toElement(); - } } @@ -179,22 +193,37 @@ void ManipulatedCameraFrame::initFromDOMElement(const QDomElement& element) /*! Protected internal method used to handle mouse events. */ void ManipulatedCameraFrame::startAction(int ma, bool withConstraint) { - ManipulatedFrame::startAction(ma, withConstraint); - - switch (action_) - { - case QGLViewer::MOVE_FORWARD: - case QGLViewer::MOVE_BACKWARD: - case QGLViewer::DRIVE: -#if QT_VERSION >= 0x040000 - flyTimer_.setSingleShot(false); -#endif - flyTimer_.start(10); - break; - default: - break; - } + ManipulatedFrame::startAction(ma, withConstraint); + + switch (action_) + { + case QGLViewer::MOVE_FORWARD: + case QGLViewer::MOVE_BACKWARD: + case QGLViewer::DRIVE: + flyTimer_.setSingleShot(false); + flyTimer_.start(10); + break; + case QGLViewer::ROTATE: + constrainedRotationIsReversed_ = transformOf(sceneUpVector_).y < 0.0; + break; + default: + break; + } } + +void ManipulatedCameraFrame::zoom(qreal delta, const Camera * const camera) { + const qreal sceneRadius = camera->sceneRadius(); + if (zoomsOnPivotPoint_) { + Vec direction = position() - camera->pivotPoint(); + if (direction.norm() > 0.02 * sceneRadius || delta > 0.0) + translate(delta * direction); + } else { + const qreal coef = qMax(fabs((camera->frame()->coordinatesOf(camera->pivotPoint())).z), 0.2 * sceneRadius); + Vec trans(0.0, 0.0, -coef * delta); + translate(inverseTransformOf(trans)); + } +} + #endif /*! Overloading of ManipulatedFrame::mouseMoveEvent(). @@ -203,155 +232,162 @@ Motion depends on mouse binding (see mouse page for resulting displacements are basically inverted from those of a ManipulatedFrame. */ void ManipulatedCameraFrame::mouseMoveEvent(QMouseEvent* const event, Camera* const camera) { - // #CONNECTION# QGLViewer::mouseMoveEvent does the updateGL. - switch (action_) - { - case QGLViewer::TRANSLATE: - { - const QPoint delta = prevPos_ - event->pos(); - Vec trans(static_cast(delta.x()), static_cast(-delta.y()), 0.0); - // Scale to fit the screen mouse displacement - switch (camera->type()) - { - case Camera::PERSPECTIVE : - trans *= 2.0 * tan(camera->fieldOfView()/2.0) * - fabs((camera->frame()->coordinatesOf(revolveAroundPoint())).z) / camera->screenHeight(); - break; - case Camera::ORTHOGRAPHIC : - { - GLdouble w,h; - camera->getOrthoWidthHeight(w, h); - trans[0] *= 2.0 * w / camera->screenWidth(); - trans[1] *= 2.0 * h / camera->screenHeight(); - break; - } - } - translate(inverseTransformOf(translationSensitivity()*trans)); - break; - } - - case QGLViewer::MOVE_FORWARD: - { - Quaternion rot = pitchYawQuaternion(event->x(), event->y(), camera); - rotate(rot); - //#CONNECTION# wheelEvent MOVE_FORWARD case - // actual translation is made in flyUpdate(). - //translate(inverseTransformOf(Vec(0.0, 0.0, -flySpeed()))); - break; - } - - case QGLViewer::MOVE_BACKWARD: - { - Quaternion rot = pitchYawQuaternion(event->x(), event->y(), camera); - rotate(rot); - // actual translation is made in flyUpdate(). - //translate(inverseTransformOf(Vec(0.0, 0.0, flySpeed()))); - break; - } - - case QGLViewer::DRIVE: - { - Quaternion rot = turnQuaternion(event->x(), camera); - rotate(rot); - // actual translation is made in flyUpdate(). - driveSpeed_ = 0.01 * (event->y() - pressPos_.y()); - break; - } - - case QGLViewer::ZOOM: - { - //#CONNECTION# wheelEvent() ZOOM case - const float coef = qMax(fabsf((camera->frame()->coordinatesOf(camera->revolveAroundPoint())).z), 0.2f*camera->sceneRadius()); - Vec trans(0.0, 0.0, -coef * (event->y() - prevPos_.y()) / camera->screenHeight()); - translate(inverseTransformOf(trans)); - break; - } - - case QGLViewer::LOOK_AROUND: - { - Quaternion rot = pitchYawQuaternion(event->x(), event->y(), camera); - rotate(rot); - break; - } - - case QGLViewer::ROTATE: - { - Vec trans = camera->projectedCoordinatesOf(revolveAroundPoint()); - Quaternion rot = deformedBallQuaternion(event->x(), event->y(), trans[0], trans[1], camera); - //#CONNECTION# These two methods should go together (spinning detection and activation) - computeMouseSpeed(event); - setSpinningQuaternion(rot); - spin(); - break; - } - - case QGLViewer::SCREEN_ROTATE: - { - Vec trans = camera->projectedCoordinatesOf(revolveAroundPoint()); - - const float angle = atan2(event->y() - trans[1], event->x() - trans[0]) - atan2(prevPos_.y()-trans[1], prevPos_.x()-trans[0]); - - Quaternion rot(Vec(0.0, 0.0, 1.0), angle); - //#CONNECTION# These two methods should go together (spinning detection and activation) - computeMouseSpeed(event); - setSpinningQuaternion(rot); - spin(); - updateFlyUpVector(); - break; - } - - case QGLViewer::ROLL: - { - const float angle = M_PI * (event->x() - prevPos_.x()) / camera->screenWidth(); - Quaternion rot(Vec(0.0, 0.0, 1.0), angle); - rotate(rot); - setSpinningQuaternion(rot); - updateFlyUpVector(); - break; - } - - case QGLViewer::SCREEN_TRANSLATE: - { - Vec trans; - int dir = mouseOriginalDirection(event); - if (dir == 1) - trans.setValue(static_cast(prevPos_.x() - event->x()), 0.0, 0.0); - else if (dir == -1) - trans.setValue(0.0, static_cast(event->y() - prevPos_.y()), 0.0); - - switch (camera->type()) - { - case Camera::PERSPECTIVE : - trans *= 2.0 * tan(camera->fieldOfView()/2.0) * - fabs((camera->frame()->coordinatesOf(revolveAroundPoint())).z) / camera->screenHeight(); - break; - case Camera::ORTHOGRAPHIC : - { - GLdouble w,h; - camera->getOrthoWidthHeight(w, h); - trans[0] *= 2.0 * w / camera->screenWidth(); - trans[1] *= 2.0 * h / camera->screenHeight(); - break; - } - } - - translate(inverseTransformOf(translationSensitivity()*trans)); - break; - } - - case QGLViewer::ZOOM_ON_REGION: - case QGLViewer::NO_MOUSE_ACTION: - break; - } - - if (action_ != QGLViewer::NO_MOUSE_ACTION) - { - prevPos_ = event->pos(); - if (action_ != QGLViewer::ZOOM_ON_REGION) - // ZOOM_ON_REGION should not emit manipulated(). - // prevPos_ is used to draw rectangle feedback. - Q_EMIT manipulated(); - } + // #CONNECTION# QGLViewer::mouseMoveEvent does the update(). + switch (action_) + { + case QGLViewer::TRANSLATE: + { + const QPoint delta = prevPos_ - event->pos(); + Vec trans(delta.x(), -delta.y(), 0.0); + // Scale to fit the screen mouse displacement + switch (camera->type()) + { + case Camera::PERSPECTIVE : + trans *= 2.0 * tan(camera->fieldOfView()/2.0) * + fabs((camera->frame()->coordinatesOf(pivotPoint())).z) / camera->screenHeight(); + break; + case Camera::ORTHOGRAPHIC : + { + GLdouble w,h; + camera->getOrthoWidthHeight(w, h); + trans[0] *= 2.0 * w / camera->screenWidth(); + trans[1] *= 2.0 * h / camera->screenHeight(); + break; + } + } + translate(inverseTransformOf(translationSensitivity()*trans)); + break; + } + + case QGLViewer::MOVE_FORWARD: + { + Quaternion rot = pitchYawQuaternion(event->x(), event->y(), camera); + rotate(rot); + //#CONNECTION# wheelEvent MOVE_FORWARD case + // actual translation is made in flyUpdate(). + //translate(inverseTransformOf(Vec(0.0, 0.0, -flySpeed()))); + break; + } + + case QGLViewer::MOVE_BACKWARD: + { + Quaternion rot = pitchYawQuaternion(event->x(), event->y(), camera); + rotate(rot); + // actual translation is made in flyUpdate(). + //translate(inverseTransformOf(Vec(0.0, 0.0, flySpeed()))); + break; + } + + case QGLViewer::DRIVE: + { + Quaternion rot = turnQuaternion(event->x(), camera); + rotate(rot); + // actual translation is made in flyUpdate(). + driveSpeed_ = 0.01 * (event->y() - pressPos_.y()); + break; + } + + case QGLViewer::ZOOM: + { + zoom(deltaWithPrevPos(event, camera), camera); + break; + } + + case QGLViewer::LOOK_AROUND: + { + Quaternion rot = pitchYawQuaternion(event->x(), event->y(), camera); + rotate(rot); + break; + } + + case QGLViewer::ROTATE: + { + Quaternion rot; + if (rotatesAroundUpVector_) { + // Multiply by 2.0 to get on average about the same speed as with the deformed ball + qreal dx = 2.0 * rotationSensitivity() * (prevPos_.x() - event->x()) / camera->screenWidth(); + qreal dy = 2.0 * rotationSensitivity() * (prevPos_.y() - event->y()) / camera->screenHeight(); + if (constrainedRotationIsReversed_) dx = -dx; + Vec verticalAxis = transformOf(sceneUpVector_); + rot = Quaternion(verticalAxis, dx) * Quaternion(Vec(1.0, 0.0, 0.0), dy); + } else { + Vec trans = camera->projectedCoordinatesOf(pivotPoint()); + rot = deformedBallQuaternion(event->x(), event->y(), trans[0], trans[1], camera); + } + //#CONNECTION# These two methods should go together (spinning detection and activation) + computeMouseSpeed(event); + setSpinningQuaternion(rot); + spin(); + break; + } + + case QGLViewer::SCREEN_ROTATE: + { + Vec trans = camera->projectedCoordinatesOf(pivotPoint()); + + const qreal angle = atan2(event->y() - trans[1], event->x() - trans[0]) - atan2(prevPos_.y()-trans[1], prevPos_.x()-trans[0]); + + Quaternion rot(Vec(0.0, 0.0, 1.0), angle); + //#CONNECTION# These two methods should go together (spinning detection and activation) + computeMouseSpeed(event); + setSpinningQuaternion(rot); + spin(); + updateSceneUpVector(); + break; + } + + case QGLViewer::ROLL: + { + const qreal angle = M_PI * (event->x() - prevPos_.x()) / camera->screenWidth(); + Quaternion rot(Vec(0.0, 0.0, 1.0), angle); + rotate(rot); + setSpinningQuaternion(rot); + updateSceneUpVector(); + break; + } + + case QGLViewer::SCREEN_TRANSLATE: + { + Vec trans; + int dir = mouseOriginalDirection(event); + if (dir == 1) + trans.setValue(prevPos_.x() - event->x(), 0.0, 0.0); + else if (dir == -1) + trans.setValue(0.0, event->y() - prevPos_.y(), 0.0); + + switch (camera->type()) + { + case Camera::PERSPECTIVE : + trans *= 2.0 * tan(camera->fieldOfView()/2.0) * + fabs((camera->frame()->coordinatesOf(pivotPoint())).z) / camera->screenHeight(); + break; + case Camera::ORTHOGRAPHIC : + { + GLdouble w,h; + camera->getOrthoWidthHeight(w, h); + trans[0] *= 2.0 * w / camera->screenWidth(); + trans[1] *= 2.0 * h / camera->screenHeight(); + break; + } + } + + translate(inverseTransformOf(translationSensitivity()*trans)); + break; + } + + case QGLViewer::ZOOM_ON_REGION: + case QGLViewer::NO_MOUSE_ACTION: + break; + } + + if (action_ != QGLViewer::NO_MOUSE_ACTION) + { + prevPos_ = event->pos(); + if (action_ != QGLViewer::ZOOM_ON_REGION) + // ZOOM_ON_REGION should not emit manipulated(). + // prevPos_ is used to draw rectangle feedback. + Q_EMIT manipulated(); + } } @@ -359,13 +395,13 @@ void ManipulatedCameraFrame::mouseMoveEvent(QMouseEvent* const event, Camera* co terminated. */ void ManipulatedCameraFrame::mouseReleaseEvent(QMouseEvent* const event, Camera* const camera) { - if ((action_ == QGLViewer::MOVE_FORWARD) || (action_ == QGLViewer::MOVE_BACKWARD) || (action_ == QGLViewer::DRIVE)) - flyTimer_.stop(); + if ((action_ == QGLViewer::MOVE_FORWARD) || (action_ == QGLViewer::MOVE_BACKWARD) || (action_ == QGLViewer::DRIVE)) + flyTimer_.stop(); - if (action_ == QGLViewer::ZOOM_ON_REGION) - camera->fitScreenRegion(QRect(pressPos_, event->pos())); + if (action_ == QGLViewer::ZOOM_ON_REGION) + camera->fitScreenRegion(QRect(pressPos_, event->pos())); - ManipulatedFrame::mouseReleaseEvent(event, camera); + ManipulatedFrame::mouseReleaseEvent(event, camera); } /*! This is an overload of ManipulatedFrame::wheelEvent(). @@ -376,51 +412,43 @@ wheelSensitivity() while QGLViewer::MOVE_FORWARD and QGLViewer::MOVE_BACKWARD de See QGLViewer::setWheelBinding() to customize the binding. */ void ManipulatedCameraFrame::wheelEvent(QWheelEvent* const event, Camera* const camera) { - //#CONNECTION# QGLViewer::setWheelBinding, ManipulatedFrame::wheelEvent. - switch (action_) - { - case QGLViewer::ZOOM: - { - const float wheelSensitivityCoef = 8E-4f; - //#CONNECTION# mouseMoveEvent() ZOOM case - const float coef = qMax(fabsf((camera->frame()->coordinatesOf(camera->revolveAroundPoint())).z), 0.2f*camera->sceneRadius()); - Vec trans(0.0, 0.0, coef * event->delta() * wheelSensitivity() * wheelSensitivityCoef); - translate(inverseTransformOf(trans)); - Q_EMIT manipulated(); - break; - } - case QGLViewer::MOVE_FORWARD: - case QGLViewer::MOVE_BACKWARD: - //#CONNECTION# mouseMoveEvent() MOVE_FORWARD case - translate(inverseTransformOf(Vec(0.0, 0.0, 0.2*flySpeed()*event->delta()))); - Q_EMIT manipulated(); - break; - default: - break; - } - - // #CONNECTION# startAction should always be called before - if (previousConstraint_) - setConstraint(previousConstraint_); - - // The wheel triggers a fastDraw. A final updateGL is needed after the last wheel event to - // polish the rendering using draw(). Since the last wheel event does not say its name, we use - // the flyTimer_ to trigger flyUpdate(), which emits manipulated. Two wheel events - // separated by more than this delay milliseconds will trigger a draw(). - const int finalDrawAfterWheelEventDelay = 400; - - // Starts (or prolungates) the timer. -#if QT_VERSION >= 0x040000 - flyTimer_.setSingleShot(true); - flyTimer_.start(finalDrawAfterWheelEventDelay); -#else - flyTimer_.start(finalDrawAfterWheelEventDelay, true); -#endif + //#CONNECTION# QGLViewer::setWheelBinding, ManipulatedFrame::wheelEvent. + switch (action_) + { + case QGLViewer::ZOOM: + { + zoom(wheelDelta(event), camera); + Q_EMIT manipulated(); + break; + } + case QGLViewer::MOVE_FORWARD: + case QGLViewer::MOVE_BACKWARD: + //#CONNECTION# mouseMoveEvent() MOVE_FORWARD case + translate(inverseTransformOf(Vec(0.0, 0.0, 0.2*flySpeed()*event->delta()))); + Q_EMIT manipulated(); + break; + default: + break; + } + + // #CONNECTION# startAction should always be called before + if (previousConstraint_) + setConstraint(previousConstraint_); + + // The wheel triggers a fastDraw. A final update() is needed after the last wheel event to + // polish the rendering using draw(). Since the last wheel event does not say its name, we use + // the flyTimer_ to trigger flyUpdate(), which emits manipulated. Two wheel events + // separated by more than this delay milliseconds will trigger a draw(). + const int finalDrawAfterWheelEventDelay = 400; + + // Starts (or prolungates) the timer. + flyTimer_.setSingleShot(true); + flyTimer_.start(finalDrawAfterWheelEventDelay); - // This could also be done *before* manipulated is emitted, so that isManipulated() returns false. - // But then fastDraw would not be used with wheel. - // Detecting the last wheel event and forcing a final draw() is done using the timer_. - action_ = QGLViewer::NO_MOUSE_ACTION; + // This could also be done *before* manipulated is emitted, so that isManipulated() returns false. + // But then fastDraw would not be used with wheel. + // Detecting the last wheel event and forcing a final draw() is done using the timer_. + action_ = QGLViewer::NO_MOUSE_ACTION; } //////////////////////////////////////////////////////////////////////////////// @@ -428,14 +456,14 @@ void ManipulatedCameraFrame::wheelEvent(QWheelEvent* const event, Camera* const /*! Returns a Quaternion that is a rotation around current camera Y, proportionnal to the horizontal mouse position. */ Quaternion ManipulatedCameraFrame::turnQuaternion(int x, const Camera* const camera) { - return Quaternion(Vec(0.0, 1.0, 0.0), rotationSensitivity()*(prevPos_.x()-x)/camera->screenWidth()); + return Quaternion(Vec(0.0, 1.0, 0.0), rotationSensitivity()*(prevPos_.x()-x)/camera->screenWidth()); } /*! Returns a Quaternion that is the composition of two rotations, inferred from the - mouse pitch (X axis) and yaw (flyUpVector() axis). */ + mouse pitch (X axis) and yaw (sceneUpVector() axis). */ Quaternion ManipulatedCameraFrame::pitchYawQuaternion(int x, int y, const Camera* const camera) { - const Quaternion rotX(Vec(1.0, 0.0, 0.0), rotationSensitivity()*(prevPos_.y()-y)/camera->screenHeight()); - const Quaternion rotY(transformOf(flyUpVector()), rotationSensitivity()*(prevPos_.x()-x)/camera->screenWidth()); - return rotY * rotX; + const Quaternion rotX(Vec(1.0, 0.0, 0.0), rotationSensitivity()*(prevPos_.y()-y)/camera->screenHeight()); + const Quaternion rotY(transformOf(sceneUpVector()), rotationSensitivity()*(prevPos_.x()-x)/camera->screenWidth()); + return rotY * rotX; } diff --git a/octovis/src/extern/QGLViewer/manipulatedCameraFrame.h b/octovis/src/extern/QGLViewer/manipulatedCameraFrame.h index 7bb51fde..1f500ad1 100644 --- a/octovis/src/extern/QGLViewer/manipulatedCameraFrame.h +++ b/octovis/src/extern/QGLViewer/manipulatedCameraFrame.h @@ -1,8 +1,8 @@ /**************************************************************************** - Copyright (C) 2002-2013 Gilles Debunne. All rights reserved. + Copyright (C) 2002-2014 Gilles Debunne. All rights reserved. - This file is part of the QGLViewer library version 2.4.0. + This file is part of the QGLViewer library version 2.6.3. http://www.libqglviewer.com - contact@libqglviewer.com @@ -26,7 +26,7 @@ #include "manipulatedFrame.h" namespace qglviewer { - /*! \brief The ManipulatedCameraFrame class represents a ManipulatedFrame with Camera specific mouse bindings. +/*! \brief The ManipulatedCameraFrame class represents a ManipulatedFrame with Camera specific mouse bindings. \class ManipulatedCameraFrame manipulatedCameraFrame.h QGLViewer/manipulatedCameraFrame.h A ManipulatedCameraFrame is a specialization of a ManipulatedFrame, designed to be set as the @@ -34,132 +34,199 @@ namespace qglviewer { the right, the ManipulatedFrame translation goes to the right, while the ManipulatedCameraFrame has to go to the \e left, so that the \e scene seems to move to the right. - A ManipulatedCameraFrame rotates around its revolveAroundPoint(), which corresponds to the - associated Camera::revolveAroundPoint(). + A ManipulatedCameraFrame rotates around its pivotPoint(), which corresponds to the + associated Camera::pivotPoint(). A ManipulatedCameraFrame can also "fly" in the scene. It basically moves forward, and turns - according to the mouse motion. See flySpeed(), flyUpVector() and the QGLViewer::MOVE_FORWARD and + according to the mouse motion. See flySpeed(), sceneUpVector() and the QGLViewer::MOVE_FORWARD and QGLViewer::MOVE_BACKWARD QGLViewer::MouseAction. See the mouse page for a description of the possible actions that can be performed using the mouse and their bindings. \nosubgrouping */ - class QGLVIEWER_EXPORT ManipulatedCameraFrame : public ManipulatedFrame - { +class QGLVIEWER_EXPORT ManipulatedCameraFrame : public ManipulatedFrame +{ #ifndef DOXYGEN - friend class Camera; - friend class ::QGLViewer; + friend class Camera; + friend class ::QGLViewer; #endif - Q_OBJECT - - public: - ManipulatedCameraFrame(); - /*! Virtual destructor. Empty. */ - virtual ~ManipulatedCameraFrame() {}; - - ManipulatedCameraFrame(const ManipulatedCameraFrame& mcf); - ManipulatedCameraFrame& operator=(const ManipulatedCameraFrame& mcf); - - /*! @name Revolve around point */ - //@{ - public: - /*! Returns the point the ManipulatedCameraFrame revolves around when rotated. - - It is defined in the world coordinate system. Default value is (0,0,0). - - When the ManipulatedCameraFrame is associated to a Camera, Camera::revolveAroundPoint() also - returns this value. This point can interactively be changed using the mouse (see - QGLViewer::RAP_FROM_PIXEL and QGLViewer::RAP_IS_CENTER in the mouse - page). */ - Vec revolveAroundPoint() const { return revolveAroundPoint_; } - /*! Sets the revolveAroundPoint(), defined in the world coordinate system. */ - void setRevolveAroundPoint(const Vec& revolveAroundPoint) { revolveAroundPoint_ = revolveAroundPoint; } - //@} - - /*! @name Fly parameters */ - //@{ - public Q_SLOTS: - /*! Sets the flySpeed(), defined in OpenGL units. - - Default value is 0.0, but it is modified according to the QGLViewer::sceneRadius() when the - ManipulatedCameraFrame is set as the Camera::frame(). */ - void setFlySpeed(float speed) { flySpeed_ = speed; }; - - /*! Sets the flyUpVector(), defined in the world coordinate system. - - Default value is (0,1,0), but it is updated by the Camera when set as its Camera::frame(). Use - Camera::setUpVector() instead in that case. */ - void setFlyUpVector(const Vec& up) { flyUpVector_ = up; }; - - public: - /*! Returns the fly speed, expressed in OpenGL units. - - It corresponds to the incremental displacement that is periodically applied to the - ManipulatedCameraFrame position when a QGLViewer::MOVE_FORWARD or QGLViewer::MOVE_BACKWARD - QGLViewer::MouseAction is proceeded. - - \attention When the ManipulatedCameraFrame is set as the Camera::frame(), this value is set - according to the QGLViewer::sceneRadius() by QGLViewer::setSceneRadius(). */ - float flySpeed() const { return flySpeed_; }; - - /*! Returns the up vector used in fly mode, expressed in the world coordinate system. - - Fly mode corresponds to the QGLViewer::MOVE_FORWARD and QGLViewer::MOVE_BACKWARD - QGLViewer::MouseAction bindings. In these modes, horizontal displacements of the mouse rotate - the ManipulatedCameraFrame around this vector. Vertical displacements rotate always around the - Camera \c X axis. - - Default value is (0,1,0), but it is updated by the Camera when set as its Camera::frame(). - Camera::setOrientation() and Camera::setUpVector()) modify this value and should be used - instead. */ - Vec flyUpVector() const { return flyUpVector_; }; - //@} - - /*! @name Mouse event handlers */ - //@{ - protected: - virtual void mouseReleaseEvent(QMouseEvent* const event, Camera* const camera); - virtual void mouseMoveEvent (QMouseEvent* const event, Camera* const camera); - virtual void wheelEvent (QWheelEvent* const event, Camera* const camera); - //@} - - /*! @name Spinning */ - //@{ - protected Q_SLOTS: - virtual void spin(); - //@} - - /*! @name XML representation */ - //@{ - public: - virtual QDomElement domElement(const QString& name, QDomDocument& document) const; - public Q_SLOTS: - virtual void initFromDOMElement(const QDomElement& element); - //@} + Q_OBJECT + +public: + ManipulatedCameraFrame(); + /*! Virtual destructor. Empty. */ + virtual ~ManipulatedCameraFrame() {} + + ManipulatedCameraFrame(const ManipulatedCameraFrame& mcf); + ManipulatedCameraFrame& operator=(const ManipulatedCameraFrame& mcf); + + /*! @name Pivot point */ + //@{ +public: + /*! Returns the point the ManipulatedCameraFrame pivot point, around which the camera rotates. + + It is defined in the world coordinate system. Default value is (0,0,0). + + When the ManipulatedCameraFrame is associated to a Camera, Camera::pivotPoint() also + returns this value. This point can interactively be changed using the mouse (see + Camera::setPivotPointFromPixel() and QGLViewer::RAP_FROM_PIXEL and QGLViewer::RAP_IS_CENTER + in the mouse page). */ + Vec pivotPoint() const { return pivotPoint_; } + /*! Sets the pivotPoint(), defined in the world coordinate system. */ + void setPivotPoint(const Vec& point) { pivotPoint_ = point; } + +#ifndef DOXYGEN + Vec revolveAroundPoint() const { qWarning("revolveAroundPoint() is deprecated, use pivotPoint() instead"); return pivotPoint(); } + void setRevolveArountPoint(const Vec& point) { qWarning("setRevolveAroundPoint() is deprecated, use setPivotPoint() instead"); setPivotPoint(point); } +#endif + //@} + + /*! @name Camera manipulation */ + //@{ +public: + /*! Returns \c true when the frame's rotation is constrained around the sceneUpVector(), + and \c false otherwise, when the rotation is completely free (default). + + In free mode, the associated camera can be arbitrarily rotated in the scene, along its + three axis, thus possibly leading to any arbitrary orientation. + + When you setRotatesAroundUpVector() to \c true, the sceneUpVector() defines a + 'vertical' direction around which the camera rotates. The camera can rotate left + or right, around this axis. It can also be moved up or down to show the 'top' and + 'bottom' views of the scene. As a result, the sceneUpVector() will always appear vertical + in the scene, and the horizon is preserved and stays projected along the camera's + horizontal axis. + + Note that setting this value to \c true when the sceneUpVector() is not already + vertically projected will break these invariants. It will also limit the possible movement + of the camera, possibly up to a lock when the sceneUpVector() is projected horizontally. + Use Camera::setUpVector() to define the sceneUpVector() and align the camera before calling + this method to ensure this does not happen. */ + bool rotatesAroundUpVector() const { return rotatesAroundUpVector_; } + /*! Sets the value of rotatesAroundUpVector(). + + Default value is false (free rotation). */ + void setRotatesAroundUpVector(bool constrained) { rotatesAroundUpVector_ = constrained; } + + /*! Returns whether or not the QGLViewer::ZOOM action zooms on the pivot point. + + When set to \c false (default), a zoom action will move the camera along its Camera::viewDirection(), + i.e. back and forth along a direction perpendicular to the projection screen. + + setZoomsOnPivotPoint() to \c true will move the camera along an axis defined by the + Camera::pivotPoint() and its current position instead. As a result, the projected position of the + pivot point on screen will stay the same during a zoom. */ + bool zoomsOnPivotPoint() const { return zoomsOnPivotPoint_; } + /*! Sets the value of zoomsOnPivotPoint(). + + Default value is false. */ + void setZoomsOnPivotPoint(bool enabled) { zoomsOnPivotPoint_ = enabled; } + +private: +#ifndef DOXYGEN + void zoom(qreal delta, const Camera * const camera); +#endif + //@} + + /*! @name Fly parameters */ + //@{ +public Q_SLOTS: + /*! Sets the flySpeed(), defined in OpenGL units. + + Default value is 0.0, but it is modified according to the QGLViewer::sceneRadius() when the + ManipulatedCameraFrame is set as the Camera::frame(). */ + void setFlySpeed(qreal speed) { flySpeed_ = speed; } + + /*! Sets the sceneUpVector(), defined in the world coordinate system. + + Default value is (0,1,0), but it is updated by the Camera when this object is set as its Camera::frame(). + Using Camera::setUpVector() instead is probably a better solution. */ + void setSceneUpVector(const Vec& up) { sceneUpVector_ = up; } + +public: + /*! Returns the fly speed, expressed in OpenGL units. + + It corresponds to the incremental displacement that is periodically applied to the + ManipulatedCameraFrame position when a QGLViewer::MOVE_FORWARD or QGLViewer::MOVE_BACKWARD + QGLViewer::MouseAction is proceeded. + + \attention When the ManipulatedCameraFrame is set as the Camera::frame(), this value is set + according to the QGLViewer::sceneRadius() by QGLViewer::setSceneRadius(). */ + qreal flySpeed() const { return flySpeed_; } + + /*! Returns the up vector of the scene, expressed in the world coordinate system. + + In 'fly mode' (corresponding to the QGLViewer::MOVE_FORWARD and QGLViewer::MOVE_BACKWARD + QGLViewer::MouseAction bindings), horizontal displacements of the mouse rotate + the ManipulatedCameraFrame around this vector. Vertical displacements rotate always around the + Camera \c X axis. + + This value is also used when setRotationIsConstrained() is set to \c true to define the up vector + (and incidentally the 'horizon' plane) around which the camera will rotate. + + Default value is (0,1,0), but it is updated by the Camera when this object is set as its Camera::frame(). + Camera::setOrientation() and Camera::setUpVector()) direclty modify this value and should be used + instead. */ + Vec sceneUpVector() const { return sceneUpVector_; } + +#ifndef DOXYGEN + Vec flyUpVector() const; + void setFlyUpVector(const Vec& up); +#endif + //@} + + /*! @name Mouse event handlers */ + //@{ +protected: + virtual void mouseReleaseEvent(QMouseEvent* const event, Camera* const camera); + virtual void mouseMoveEvent (QMouseEvent* const event, Camera* const camera); + virtual void wheelEvent (QWheelEvent* const event, Camera* const camera); + //@} + + /*! @name Spinning */ + //@{ +protected Q_SLOTS: + virtual void spin(); + //@} + + /*! @name XML representation */ + //@{ +public: + virtual QDomElement domElement(const QString& name, QDomDocument& document) const; +public Q_SLOTS: + virtual void initFromDOMElement(const QDomElement& element); + //@} #ifndef DOXYGEN - protected: - virtual void startAction(int ma, bool withConstraint=true); // int is really a QGLViewer::MouseAction +protected: + virtual void startAction(int ma, bool withConstraint=true); // int is really a QGLViewer::MouseAction #endif - private Q_SLOTS: - virtual void flyUpdate(); +private Q_SLOTS: + virtual void flyUpdate(); + +private: + void updateSceneUpVector(); + Quaternion turnQuaternion(int x, const Camera* const camera); + Quaternion pitchYawQuaternion(int x, int y, const Camera* const camera); + +private: + // Fly mode data + qreal flySpeed_; + qreal driveSpeed_; + Vec sceneUpVector_; + QTimer flyTimer_; - private: - void updateFlyUpVector(); - Quaternion turnQuaternion(int x, const Camera* const camera); - Quaternion pitchYawQuaternion(int x, int y, const Camera* const camera); + bool rotatesAroundUpVector_; + // Inverse the direction of an horizontal mouse motion. Depends on the projected + // screen orientation of the vertical axis when the mouse button is pressed. + bool constrainedRotationIsReversed_; - private: - // Fly mode data - float flySpeed_; - float driveSpeed_; - Vec flyUpVector_; - QTimer flyTimer_; + bool zoomsOnPivotPoint_; - Vec revolveAroundPoint_; - }; + Vec pivotPoint_; +}; } // namespace qglviewer diff --git a/octovis/src/extern/QGLViewer/manipulatedFrame.cpp b/octovis/src/extern/QGLViewer/manipulatedFrame.cpp index bdececde..b6b2d72b 100644 --- a/octovis/src/extern/QGLViewer/manipulatedFrame.cpp +++ b/octovis/src/extern/QGLViewer/manipulatedFrame.cpp @@ -1,8 +1,8 @@ /**************************************************************************** - Copyright (C) 2002-2013 Gilles Debunne. All rights reserved. + Copyright (C) 2002-2014 Gilles Debunne. All rights reserved. - This file is part of the QGLViewer library version 2.4.0. + This file is part of the QGLViewer library version 2.6.3. http://www.libqglviewer.com - contact@libqglviewer.com @@ -22,14 +22,13 @@ #include "domUtils.h" #include "manipulatedFrame.h" +#include "manipulatedCameraFrame.h" #include "qglviewer.h" #include "camera.h" #include -#if QT_VERSION >= 0x040000 -# include -#endif +#include using namespace qglviewer; using namespace std; @@ -42,42 +41,45 @@ using namespace std; The different sensitivities are set to their default values (see rotationSensitivity(), translationSensitivity(), spinningSensitivity() and wheelSensitivity()). */ ManipulatedFrame::ManipulatedFrame() - : action_(QGLViewer::NO_MOUSE_ACTION), keepsGrabbingMouse_(false) + : action_(QGLViewer::NO_MOUSE_ACTION), keepsGrabbingMouse_(false) { - // #CONNECTION# initFromDOMElement and accessor docs - setRotationSensitivity(1.0f); - setTranslationSensitivity(1.0f); - setSpinningSensitivity(0.3f); - setWheelSensitivity(1.0f); + // #CONNECTION# initFromDOMElement and accessor docs + setRotationSensitivity(1.0); + setTranslationSensitivity(1.0); + setSpinningSensitivity(0.3); + setWheelSensitivity(1.0); + setZoomSensitivity(1.0); - isSpinning_ = false; - previousConstraint_ = NULL; + isSpinning_ = false; + previousConstraint_ = NULL; - connect(&spinningTimer_, SIGNAL(timeout()), SLOT(spinUpdate())); + connect(&spinningTimer_, SIGNAL(timeout()), SLOT(spinUpdate())); } /*! Equal operator. Calls Frame::operator=() and then copy attributes. */ ManipulatedFrame& ManipulatedFrame::operator=(const ManipulatedFrame& mf) { - Frame::operator=(mf); + Frame::operator=(mf); - setRotationSensitivity(mf.rotationSensitivity()); - setTranslationSensitivity(mf.translationSensitivity()); - setSpinningSensitivity(mf.spinningSensitivity()); - setWheelSensitivity(mf.wheelSensitivity()); + setRotationSensitivity(mf.rotationSensitivity()); + setTranslationSensitivity(mf.translationSensitivity()); + setSpinningSensitivity(mf.spinningSensitivity()); + setWheelSensitivity(mf.wheelSensitivity()); + setZoomSensitivity(mf.zoomSensitivity()); - mouseSpeed_ = 0.0; - dirIsFixed_ = false; - keepsGrabbingMouse_ = false; + mouseSpeed_ = 0.0; + dirIsFixed_ = false; + keepsGrabbingMouse_ = false; + action_ = QGLViewer::NO_MOUSE_ACTION; - return *this; + return *this; } /*! Copy constructor. Performs a deep copy of all attributes using operator=(). */ ManipulatedFrame::ManipulatedFrame(const ManipulatedFrame& mf) - : Frame(mf), MouseGrabber() + : Frame(mf), MouseGrabber() { - (*this)=mf; + (*this)=mf; } //////////////////////////////////////////////////////////////////////////////// @@ -90,9 +92,9 @@ Camera::projectedCoordinatesOf() position(). See the mouseGrabber example for an illustration. */ void ManipulatedFrame::checkIfGrabsMouse(int x, int y, const Camera* const camera) { - const int thresold = 10; - const Vec proj = camera->projectedCoordinatesOf(position()); - setGrabsMouse(keepsGrabbingMouse_ || ((fabs(x-proj.x) < thresold) && (fabs(y-proj.y) < thresold))); + const int thresold = 10; + const Vec proj = camera->projectedCoordinatesOf(position()); + setGrabsMouse(keepsGrabbingMouse_ || ((fabs(x-proj.x) < thresold) && (fabs(y-proj.y) < thresold))); } //////////////////////////////////////////////////////////////////////////////// @@ -113,14 +115,15 @@ void ManipulatedFrame::checkIfGrabsMouse(int x, int y, const Camera* const camer Camera::domElement()... */ QDomElement ManipulatedFrame::domElement(const QString& name, QDomDocument& document) const { - QDomElement e = Frame::domElement(name, document); - QDomElement mp = document.createElement("ManipulatedParameters"); - mp.setAttribute("rotSens", QString::number(rotationSensitivity())); - mp.setAttribute("transSens", QString::number(translationSensitivity())); - mp.setAttribute("spinSens", QString::number(spinningSensitivity())); - mp.setAttribute("wheelSens", QString::number(wheelSensitivity())); - e.appendChild(mp); - return e; + QDomElement e = Frame::domElement(name, document); + QDomElement mp = document.createElement("ManipulatedParameters"); + mp.setAttribute("rotSens", QString::number(rotationSensitivity())); + mp.setAttribute("transSens", QString::number(translationSensitivity())); + mp.setAttribute("spinSens", QString::number(spinningSensitivity())); + mp.setAttribute("wheelSens", QString::number(wheelSensitivity())); + mp.setAttribute("zoomSens", QString::number(zoomSensitivity())); + e.appendChild(mp); + return e; } /*! Restores the ManipulatedFrame state from a \c QDomElement created by domElement(). @@ -134,25 +137,26 @@ Note that constraint() and referenceFrame() are not restored and are left unchan See Vec::initFromDOMElement() for a complete code example. */ void ManipulatedFrame::initFromDOMElement(const QDomElement& element) { - // Not called since it would set constraint() and referenceFrame() to NULL. - // *this = ManipulatedFrame(); - Frame::initFromDOMElement(element); + // Not called since it would set constraint() and referenceFrame() to NULL. + // *this = ManipulatedFrame(); + Frame::initFromDOMElement(element); - stopSpinning(); + stopSpinning(); - QDomElement child=element.firstChild().toElement(); - while (!child.isNull()) - { - if (child.tagName() == "ManipulatedParameters") + QDomElement child=element.firstChild().toElement(); + while (!child.isNull()) { - // #CONNECTION# constructor default values and accessor docs - setRotationSensitivity (DomUtils::floatFromDom(child, "rotSens", 1.0f)); - setTranslationSensitivity(DomUtils::floatFromDom(child, "transSens", 1.0f)); - setSpinningSensitivity (DomUtils::floatFromDom(child, "spinSens", 0.3f)); - setWheelSensitivity (DomUtils::floatFromDom(child, "wheelSens", 1.0f)); + if (child.tagName() == "ManipulatedParameters") + { + // #CONNECTION# constructor default values and accessor docs + setRotationSensitivity (DomUtils::qrealFromDom(child, "rotSens", 1.0)); + setTranslationSensitivity(DomUtils::qrealFromDom(child, "transSens", 1.0)); + setSpinningSensitivity (DomUtils::qrealFromDom(child, "spinSens", 0.3)); + setWheelSensitivity (DomUtils::qrealFromDom(child, "wheelSens", 1.0)); + setZoomSensitivity (DomUtils::qrealFromDom(child, "zoomSens", 1.0)); + } + child = child.nextSibling().toElement(); } - child = child.nextSibling().toElement(); - } } @@ -169,7 +173,7 @@ void ManipulatedFrame::initFromDOMElement(const QDomElement& element) interactive camera displacements. */ bool ManipulatedFrame::isManipulated() const { - return action_ != QGLViewer::NO_MOUSE_ACTION; + return action_ != QGLViewer::NO_MOUSE_ACTION; } /*! Starts the spinning of the ManipulatedFrame. @@ -178,15 +182,15 @@ This method starts a timer that will call spin() every \p updateInterval millise ManipulatedFrame isSpinning() until you call stopSpinning(). */ void ManipulatedFrame::startSpinning(int updateInterval) { - isSpinning_ = true; - spinningTimer_.start(updateInterval); + isSpinning_ = true; + spinningTimer_.start(updateInterval); } /*! Rotates the ManipulatedFrame by its spinningQuaternion(). Called by a timer when the ManipulatedFrame isSpinning(). */ void ManipulatedFrame::spin() { - rotate(spinningQuaternion()); + rotate(spinningQuaternion()); } /* spin() and spinUpdate() differ since spin can be used by itself (for instance by @@ -195,78 +199,101 @@ void ManipulatedFrame::spin() with this design. */ void ManipulatedFrame::spinUpdate() { - spin(); - Q_EMIT spun(); + spin(); + Q_EMIT spun(); } #ifndef DOXYGEN /*! Protected internal method used to handle mouse events. */ void ManipulatedFrame::startAction(int ma, bool withConstraint) { - action_ = (QGLViewer::MouseAction)(ma); - - // #CONNECTION# manipulatedFrame::wheelEvent, manipulatedCameraFrame::wheelEvent and mouseReleaseEvent() - // restore previous constraint - if (withConstraint) - previousConstraint_ = NULL; - else - { - previousConstraint_ = constraint(); - setConstraint(NULL); - } - - switch (action_) - { - case QGLViewer::ROTATE: - case QGLViewer::SCREEN_ROTATE: - mouseSpeed_ = 0.0; - stopSpinning(); - break; - - case QGLViewer::SCREEN_TRANSLATE: - dirIsFixed_ = false; - break; - - default: - break; - } + action_ = (QGLViewer::MouseAction)(ma); + + // #CONNECTION# manipulatedFrame::wheelEvent, manipulatedCameraFrame::wheelEvent and mouseReleaseEvent() + // restore previous constraint + if (withConstraint) + previousConstraint_ = NULL; + else + { + previousConstraint_ = constraint(); + setConstraint(NULL); + } + + switch (action_) + { + case QGLViewer::ROTATE: + case QGLViewer::SCREEN_ROTATE: + mouseSpeed_ = 0.0; + stopSpinning(); + break; + + case QGLViewer::SCREEN_TRANSLATE: + dirIsFixed_ = false; + break; + + default: + break; + } } /*! Updates mouse speed, measured in pixels/milliseconds. Should be called by any method which wants to use mouse speed. Currently used to trigger spinning in mouseReleaseEvent(). */ void ManipulatedFrame::computeMouseSpeed(const QMouseEvent* const e) { - const QPoint delta = (e->pos() - prevPos_); - const float dist = sqrt(static_cast(delta.x()*delta.x() + delta.y()*delta.y())); - delay_ = last_move_time.restart(); - if (delay_ == 0) - // Less than a millisecond: assume delay = 1ms - mouseSpeed_ = dist; - else - mouseSpeed_ = dist/delay_; + const QPoint delta = (e->pos() - prevPos_); + const qreal dist = sqrt(qreal(delta.x()*delta.x() + delta.y()*delta.y())); + delay_ = last_move_time.restart(); + if (delay_ == 0) + // Less than a millisecond: assume delay = 1ms + mouseSpeed_ = dist; + else + mouseSpeed_ = dist/delay_; } /*! Return 1 if mouse motion was started horizontally and -1 if it was more vertical. Returns 0 if this could not be determined yet (perfect diagonal motion, rare). */ int ManipulatedFrame::mouseOriginalDirection(const QMouseEvent* const e) { - static bool horiz = true; // Two simultaneous manipulatedFrame require two mice ! - - if (!dirIsFixed_) - { - const QPoint delta = e->pos() - pressPos_; - dirIsFixed_ = abs(delta.x()) != abs(delta.y()); - horiz = abs(delta.x()) > abs(delta.y()); - } - - if (dirIsFixed_) - if (horiz) - return 1; - else - return -1; - else - return 0; + static bool horiz = true; // Two simultaneous manipulatedFrame require two mice ! + + if (!dirIsFixed_) + { + const QPoint delta = e->pos() - pressPos_; + dirIsFixed_ = abs(delta.x()) != abs(delta.y()); + horiz = abs(delta.x()) > abs(delta.y()); + } + + if (dirIsFixed_) + if (horiz) + return 1; + else + return -1; + else + return 0; } + +qreal ManipulatedFrame::deltaWithPrevPos(QMouseEvent* const event, Camera* const camera) const { + qreal dx = qreal(event->x() - prevPos_.x()) / camera->screenWidth(); + qreal dy = qreal(event->y() - prevPos_.y()) / camera->screenHeight(); + + qreal value = fabs(dx) > fabs(dy) ? dx : dy; + return value * zoomSensitivity(); +} + +qreal ManipulatedFrame::wheelDelta(const QWheelEvent* event) const { + static const qreal WHEEL_SENSITIVITY_COEF = 8E-4; + return event->delta() * wheelSensitivity() * WHEEL_SENSITIVITY_COEF; +} + +void ManipulatedFrame::zoom(qreal delta, const Camera * const camera) { + Vec trans(0.0, 0.0, (camera->position() - position()).norm() * delta); + + trans = camera->frame()->orientation().rotate(trans); + if (referenceFrame()) + trans = referenceFrame()->transformOf(trans); + translate(trans); +} + #endif // DOXYGEN /*! Initiates the ManipulatedFrame mouse manipulation. @@ -277,19 +304,17 @@ The mouse behavior depends on which button is pressed. See the = 0x040000 -# include -# include -# include -#else -# include -# include -# include -#endif +#include +#include +#include namespace qglviewer { - /*! \brief A ManipulatedFrame is a Frame that can be rotated and translated using the mouse. +/*! \brief A ManipulatedFrame is a Frame that can be rotated and translated using the mouse. \class ManipulatedFrame manipulatedFrame.h QGLViewer/manipulatedFrame.h It converts the mouse motion into a translation and an orientation updates. A ManipulatedFrame is @@ -51,10 +46,10 @@ namespace qglviewer { draw() { - glPushMatrix(); - glMultMatrixd(manipulatedFrame()->matrix()); - // draw the manipulated object here - glPopMatrix(); + glPushMatrix(); + glMultMatrixd(manipulatedFrame()->matrix()); + // draw the manipulated object here + glPopMatrix(); } \endcode See the manipulatedFrame example for a complete @@ -91,217 +86,249 @@ namespace qglviewer { display (as is done with QGLViewer::fastDraw()). The ManipulatedFrame also emits a manipulated() signal each time its state is modified by the - mouse. This signal is automatically connected to the QGLViewer::updateGL() slot when the + mouse. This signal is automatically connected to the QGLViewer::update() slot when the ManipulatedFrame is attached to a viewer using QGLViewer::setManipulatedFrame(). You can make the ManipulatedFrame spin() if you release the rotation mouse button while moving the mouse fast enough (see spinningSensitivity()). See also translationSensitivity() and rotationSensitivity() for sensitivity tuning. \nosubgrouping */ - class QGLVIEWER_EXPORT ManipulatedFrame : public Frame, public MouseGrabber - { +class QGLVIEWER_EXPORT ManipulatedFrame : public Frame, public MouseGrabber +{ #ifndef DOXYGEN - friend class Camera; - friend class ::QGLViewer; + friend class Camera; + friend class ::QGLViewer; #endif - Q_OBJECT + Q_OBJECT + +public: + ManipulatedFrame(); + /*! Virtual destructor. Empty. */ + virtual ~ManipulatedFrame() {} + + ManipulatedFrame(const ManipulatedFrame& mf); + ManipulatedFrame& operator=(const ManipulatedFrame& mf); + +Q_SIGNALS: + /*! This signal is emitted when ever the ManipulatedFrame is manipulated (i.e. rotated or + translated) using the mouse. Connect this signal to any object that should be notified. - public: - ManipulatedFrame(); - /*! Virtual destructor. Empty. */ - virtual ~ManipulatedFrame() {}; + Note that this signal is automatically connected to the QGLViewer::update() slot, when the + ManipulatedFrame is attached to a viewer using QGLViewer::setManipulatedFrame(), which is + probably all you need. - ManipulatedFrame(const ManipulatedFrame& mf); - ManipulatedFrame& operator=(const ManipulatedFrame& mf); + Use the QGLViewer::QGLViewerPool() if you need to connect this signal to all the viewers. - Q_SIGNALS: - /*! This signal is emitted when ever the ManipulatedFrame is manipulated (i.e. rotated or - translated) using the mouse. Connect this signal to any object that should be notified. + See also the spun(), modified(), interpolated() and KeyFrameInterpolator::interpolated() + signals' documentations. */ + void manipulated(); - Note that this signal is automatically connected to the QGLViewer::updateGL() slot, when the - ManipulatedFrame is attached to a viewer using QGLViewer::setManipulatedFrame(), which is - probably all you need. + /*! This signal is emitted when the ManipulatedFrame isSpinning(). - Use the QGLViewer::QGLViewerPool() if you need to connect this signal to all the viewers. - - See also the spun(), modified(), interpolated() and KeyFrameInterpolator::interpolated() - signals' documentations. */ - void manipulated(); - - /*! This signal is emitted when the ManipulatedFrame isSpinning(). - - Note that for the QGLViewer::manipulatedFrame(), this signal is automatically connected to the - QGLViewer::updateGL() slot. - - Connect this signal to any object that should be notified. Use the QGLViewer::QGLViewerPool() if - you need to connect this signal to all the viewers. - - See also the manipulated(), modified(), interpolated() and KeyFrameInterpolator::interpolated() - signals' documentations. */ - void spun(); - - /*! @name Manipulation sensitivity */ - //@{ - public Q_SLOTS: - /*! Defines the rotationSensitivity(). */ - void setRotationSensitivity(float sensitivity) { rotSensitivity_ = sensitivity; }; - /*! Defines the translationSensitivity(). */ - void setTranslationSensitivity(float sensitivity) { transSensitivity_ = sensitivity; }; - /*! Defines the spinningSensitivity(), in pixels per milliseconds. */ - void setSpinningSensitivity(float sensitivity) { spinningSensitivity_ = sensitivity; }; - /*! Defines the wheelSensitivity(). */ - void setWheelSensitivity(float sensitivity) { wheelSensitivity_ = sensitivity; }; - public: - /*! Returns the influence of a mouse displacement on the ManipulatedFrame rotation. - - Default value is 1.0. With an identical mouse displacement, a higher value will generate a - larger rotation (and inversely for lower values). A 0.0 value will forbid ManipulatedFrame mouse - rotation (see also constraint()). - - See also setRotationSensitivity(), translationSensitivity(), spinningSensitivity() and - wheelSensitivity(). */ - float rotationSensitivity() const { return rotSensitivity_; }; - /*! Returns the influence of a mouse displacement on the ManipulatedFrame translation. - - Default value is 1.0. You should not have to modify this value, since with 1.0 the - ManipulatedFrame precisely stays under the mouse cursor. - - With an identical mouse displacement, a higher value will generate a larger translation (and - inversely for lower values). A 0.0 value will forbid ManipulatedFrame mouse translation (see - also constraint()). - - \note When the ManipulatedFrame is used to move a \e Camera (see the ManipulatedCameraFrame - class documentation), after zooming on a small region of your scene, the camera may translate - too fast. For a camera, it is the Camera::revolveAroundPoint() that exactly matches the mouse - displacement. Hence, instead of changing the translationSensitivity(), solve the problem by - (temporarily) setting the Camera::revolveAroundPoint() to a point on the zoomed region (see the - QGLViewer::RAP_FROM_PIXEL mouse binding in the mouse page). - - See also setTranslationSensitivity(), rotationSensitivity(), spinningSensitivity() and - wheelSensitivity(). */ - float translationSensitivity() const { return transSensitivity_; }; - /*! Returns the minimum mouse speed required (at button release) to make the ManipulatedFrame - spin(). - - See spin(), spinningQuaternion() and startSpinning() for details. - - Mouse speed is expressed in pixels per milliseconds. Default value is 0.3 (300 pixels per - second). Use setSpinningSensitivity() to tune this value. A higher value will make spinning more - difficult (a value of 100.0 forbids spinning in practice). - - See also setSpinningSensitivity(), translationSensitivity(), rotationSensitivity() and - wheelSensitivity(). */ - float spinningSensitivity() const { return spinningSensitivity_; }; - /*! Returns the mouse wheel sensitivity. - - Default value is 1.0. A higher value will make the wheel action more efficient (usually meaning - a faster zoom). Use a negative value to invert the zoom in and out directions. - - See also setWheelSensitivity(), translationSensitivity(), rotationSensitivity() and - spinningSensitivity(). */ - float wheelSensitivity() const { return wheelSensitivity_; }; - //@} - - - /*! @name Spinning */ - //@{ - public: - /*! Returns \c true when the ManipulatedFrame is spinning. - - During spinning, spin() rotates the ManipulatedFrame by its spinningQuaternion() at a frequency - defined when the ManipulatedFrame startSpinning(). - - Use startSpinning() and stopSpinning() to change this state. Default value is \c false. */ - bool isSpinning() const { return isSpinning_; }; - /*! Returns the incremental rotation that is applied by spin() to the ManipulatedFrame - orientation when it isSpinning(). - - Default value is a null rotation (identity Quaternion). Use setSpinningQuaternion() to change - this value. - - The spinningQuaternion() axis is defined in the ManipulatedFrame coordinate system. You can use - Frame::transformOfFrom() to convert this axis from an other Frame coordinate system. */ - Quaternion spinningQuaternion() const { return spinningQuaternion_; } - public Q_SLOTS: - /*! Defines the spinningQuaternion(). Its axis is defined in the ManipulatedFrame coordinate - system. */ - void setSpinningQuaternion(const Quaternion& spinningQuaternion) { spinningQuaternion_ = spinningQuaternion; } - virtual void startSpinning(int updateInterval); - /*! Stops the spinning motion started using startSpinning(). isSpinning() will return \c false - after this call. */ - virtual void stopSpinning() { spinningTimer_.stop(); isSpinning_ = false; }; - protected Q_SLOTS: - virtual void spin(); - private Q_SLOTS: - void spinUpdate(); - //@} - - /*! @name Mouse event handlers */ - //@{ - protected: - virtual void mousePressEvent (QMouseEvent* const event, Camera* const camera); - virtual void mouseMoveEvent (QMouseEvent* const event, Camera* const camera); - virtual void mouseReleaseEvent (QMouseEvent* const event, Camera* const camera); - virtual void mouseDoubleClickEvent(QMouseEvent* const event, Camera* const camera); - virtual void wheelEvent (QWheelEvent* const event, Camera* const camera); - //@} - - public: - /*! @name Current state */ - //@{ - bool isManipulated() const; - //@} - - /*! @name MouseGrabber implementation */ - //@{ - public: - virtual void checkIfGrabsMouse(int x, int y, const Camera* const camera); - //@} - - /*! @name XML representation */ - //@{ - public: - virtual QDomElement domElement(const QString& name, QDomDocument& document) const; - public Q_SLOTS: - virtual void initFromDOMElement(const QDomElement& element); - //@} + Note that for the QGLViewer::manipulatedFrame(), this signal is automatically connected to the + QGLViewer::update() slot. + + Connect this signal to any object that should be notified. Use the QGLViewer::QGLViewerPool() if + you need to connect this signal to all the viewers. + + See also the manipulated(), modified(), interpolated() and KeyFrameInterpolator::interpolated() + signals' documentations. */ + void spun(); + + /*! @name Manipulation sensitivity */ + //@{ +public Q_SLOTS: + /*! Defines the rotationSensitivity(). */ + void setRotationSensitivity(qreal sensitivity) { rotationSensitivity_ = sensitivity; } + /*! Defines the translationSensitivity(). */ + void setTranslationSensitivity(qreal sensitivity) { translationSensitivity_ = sensitivity; } + /*! Defines the spinningSensitivity(), in pixels per milliseconds. */ + void setSpinningSensitivity(qreal sensitivity) { spinningSensitivity_ = sensitivity; } + /*! Defines the wheelSensitivity(). */ + void setWheelSensitivity(qreal sensitivity) { wheelSensitivity_ = sensitivity; } + /*! Defines the zoomSensitivity(). */ + void setZoomSensitivity(qreal sensitivity) { zoomSensitivity_ = sensitivity; } + +public: + /*! Returns the influence of a mouse displacement on the ManipulatedFrame rotation. + + Default value is 1.0. With an identical mouse displacement, a higher value will generate a + larger rotation (and inversely for lower values). A 0.0 value will forbid ManipulatedFrame mouse + rotation (see also constraint()). + + See also setRotationSensitivity(), translationSensitivity(), spinningSensitivity() and + wheelSensitivity(). */ + qreal rotationSensitivity() const { return rotationSensitivity_; } + /*! Returns the influence of a mouse displacement on the ManipulatedFrame translation. + + Default value is 1.0. You should not have to modify this value, since with 1.0 the + ManipulatedFrame precisely stays under the mouse cursor. + + With an identical mouse displacement, a higher value will generate a larger translation (and + inversely for lower values). A 0.0 value will forbid ManipulatedFrame mouse translation (see + also constraint()). + + \note When the ManipulatedFrame is used to move a \e Camera (see the ManipulatedCameraFrame + class documentation), after zooming on a small region of your scene, the camera may translate + too fast. For a camera, it is the Camera::pivotPoint() that exactly matches the mouse + displacement. Hence, instead of changing the translationSensitivity(), solve the problem by + (temporarily) setting the Camera::pivotPoint() to a point on the zoomed region (see the + QGLViewer::RAP_FROM_PIXEL mouse binding in the mouse page). + + See also setTranslationSensitivity(), rotationSensitivity(), spinningSensitivity() and + wheelSensitivity(). */ + qreal translationSensitivity() const { return translationSensitivity_; } + /*! Returns the minimum mouse speed required (at button release) to make the ManipulatedFrame + spin(). + + See spin(), spinningQuaternion() and startSpinning() for details. + + Mouse speed is expressed in pixels per milliseconds. Default value is 0.3 (300 pixels per + second). Use setSpinningSensitivity() to tune this value. A higher value will make spinning more + difficult (a value of 100.0 forbids spinning in practice). + + See also setSpinningSensitivity(), translationSensitivity(), rotationSensitivity() and + wheelSensitivity(). */ + qreal spinningSensitivity() const { return spinningSensitivity_; } + + /*! Returns the zoom sensitivity. + + Default value is 1.0. A higher value will make the zoom faster. + Use a negative value to invert the zoom in and out directions. + + See also setZoomSensitivity(), translationSensitivity(), rotationSensitivity() wheelSensitivity() + and spinningSensitivity(). */ + qreal zoomSensitivity() const { return zoomSensitivity_; } + /*! Returns the mouse wheel sensitivity. + + Default value is 1.0. A higher value will make the wheel action more efficient (usually meaning + a faster zoom). Use a negative value to invert the zoom in and out directions. + + See also setWheelSensitivity(), translationSensitivity(), rotationSensitivity() zoomSensitivity() + and spinningSensitivity(). */ + qreal wheelSensitivity() const { return wheelSensitivity_; } + //@} + + + /*! @name Spinning */ + //@{ +public: + /*! Returns \c true when the ManipulatedFrame is spinning. + + During spinning, spin() rotates the ManipulatedFrame by its spinningQuaternion() at a frequency + defined when the ManipulatedFrame startSpinning(). + + Use startSpinning() and stopSpinning() to change this state. Default value is \c false. */ + bool isSpinning() const { return isSpinning_; } + /*! Returns the incremental rotation that is applied by spin() to the ManipulatedFrame + orientation when it isSpinning(). + + Default value is a null rotation (identity Quaternion). Use setSpinningQuaternion() to change + this value. + + The spinningQuaternion() axis is defined in the ManipulatedFrame coordinate system. You can use + Frame::transformOfFrom() to convert this axis from an other Frame coordinate system. */ + Quaternion spinningQuaternion() const { return spinningQuaternion_; } +public Q_SLOTS: + /*! Defines the spinningQuaternion(). Its axis is defined in the ManipulatedFrame coordinate + system. */ + void setSpinningQuaternion(const Quaternion& spinningQuaternion) { spinningQuaternion_ = spinningQuaternion; } + virtual void startSpinning(int updateInterval); + /*! Stops the spinning motion started using startSpinning(). isSpinning() will return \c false + after this call. */ + virtual void stopSpinning() { spinningTimer_.stop(); isSpinning_ = false; } +protected Q_SLOTS: + virtual void spin(); +private Q_SLOTS: + void spinUpdate(); + //@} + + /*! @name Mouse event handlers */ + //@{ +protected: + virtual void mousePressEvent (QMouseEvent* const event, Camera* const camera); + virtual void mouseMoveEvent (QMouseEvent* const event, Camera* const camera); + virtual void mouseReleaseEvent (QMouseEvent* const event, Camera* const camera); + virtual void mouseDoubleClickEvent(QMouseEvent* const event, Camera* const camera); + virtual void wheelEvent (QWheelEvent* const event, Camera* const camera); + //@} + +public: + /*! @name Current state */ + //@{ + bool isManipulated() const; + /*! Returns the \c MouseAction currently applied to this ManipulatedFrame. + + Will return QGLViewer::NO_MOUSE_ACTION unless a mouse button is being pressed + and has been bound to this QGLViewer::MouseHandler. + + The binding between mouse buttons and key modifiers and MouseAction is set using + QGLViewer::setMouseBinding(Qt::Key key, Qt::KeyboardModifiers modifiers, Qt::MouseButton buttons, MouseHandler handler, MouseAction action, bool withConstraint). + */ + QGLViewer::MouseAction currentMouseAction() const { return action_; } + //@} + + /*! @name MouseGrabber implementation */ + //@{ +public: + virtual void checkIfGrabsMouse(int x, int y, const Camera* const camera); + //@} + + /*! @name XML representation */ + //@{ +public: + virtual QDomElement domElement(const QString& name, QDomDocument& document) const; +public Q_SLOTS: + virtual void initFromDOMElement(const QDomElement& element); + //@} #ifndef DOXYGEN - protected: - Quaternion deformedBallQuaternion(int x, int y, float cx, float cy, const Camera* const camera); +protected: + Quaternion deformedBallQuaternion(int x, int y, qreal cx, qreal cy, const Camera* const camera); + + QGLViewer::MouseAction action_; + Constraint* previousConstraint_; // When manipulation is without Contraint. + + virtual void startAction(int ma, bool withConstraint=true); // int is really a QGLViewer::MouseAction + void computeMouseSpeed(const QMouseEvent* const e); + int mouseOriginalDirection(const QMouseEvent* const e); + + /*! Returns a screen scaled delta from event's position to prevPos_, along the + X or Y direction, whichever has the largest magnitude. */ + qreal deltaWithPrevPos(QMouseEvent* const event, Camera* const camera) const; + /*! Returns a normalized wheel delta, proportionnal to wheelSensitivity(). */ + qreal wheelDelta(const QWheelEvent* event) const; - int action_; // Should be a QGLViewer::MouseAction, but include loop - Constraint* previousConstraint_; // When manipulation is without Contraint. + // Previous mouse position (used for incremental updates) and mouse press position. + QPoint prevPos_, pressPos_; - virtual void startAction(int ma, bool withConstraint=true); // int is really a QGLViewer::MouseAction - void computeMouseSpeed(const QMouseEvent* const e); - int mouseOriginalDirection(const QMouseEvent* const e); +private: + void zoom(qreal delta, const Camera * const camera); - // Previous mouse position (used for incremental updates) and mouse press position. - QPoint prevPos_, pressPos_; #endif // DOXYGEN - private: - // Sensitivity - float rotSensitivity_; - float transSensitivity_; - float spinningSensitivity_; - float wheelSensitivity_; - - // Mouse speed and spinning - QTime last_move_time; - float mouseSpeed_; - int delay_; - bool isSpinning_; - QTimer spinningTimer_; - Quaternion spinningQuaternion_; - - // Whether the SCREEN_TRANS direction (horizontal or vertical) is fixed or not. - bool dirIsFixed_; - - // MouseGrabber - bool keepsGrabbingMouse_; - }; +private: + // Sensitivity + qreal rotationSensitivity_; + qreal translationSensitivity_; + qreal spinningSensitivity_; + qreal wheelSensitivity_; + qreal zoomSensitivity_; + + // Mouse speed and spinning + QTime last_move_time; + qreal mouseSpeed_; + int delay_; + bool isSpinning_; + QTimer spinningTimer_; + Quaternion spinningQuaternion_; + + // Whether the SCREEN_TRANS direction (horizontal or vertical) is fixed or not. + bool dirIsFixed_; + + // MouseGrabber + bool keepsGrabbingMouse_; +}; } // namespace qglviewer diff --git a/octovis/src/extern/QGLViewer/mouseGrabber.cpp b/octovis/src/extern/QGLViewer/mouseGrabber.cpp index a214fe3b..38cfdd01 100644 --- a/octovis/src/extern/QGLViewer/mouseGrabber.cpp +++ b/octovis/src/extern/QGLViewer/mouseGrabber.cpp @@ -1,8 +1,8 @@ /**************************************************************************** - Copyright (C) 2002-2013 Gilles Debunne. All rights reserved. + Copyright (C) 2002-2014 Gilles Debunne. All rights reserved. - This file is part of the QGLViewer library version 2.4.0. + This file is part of the QGLViewer library version 2.6.3. http://www.libqglviewer.com - contact@libqglviewer.com @@ -25,19 +25,15 @@ using namespace qglviewer; // Static private variable -#if QT_VERSION >= 0x040000 QList MouseGrabber::MouseGrabberPool_; -#else -QPtrList MouseGrabber::MouseGrabberPool_; -#endif /*! Default constructor. Adds the created MouseGrabber in the MouseGrabberPool(). grabsMouse() is set to \c false. */ MouseGrabber::MouseGrabber() - : grabsMouse_(false) + : grabsMouse_(false) { - addInMouseGrabberPool(); + addInMouseGrabberPool(); } /*! Adds the MouseGrabber in the MouseGrabberPool(). @@ -50,8 +46,8 @@ tested with checkIfGrabsMouse() by the QGLViewer, and hence can no longer grab m isInMouseGrabberPool() to know the current state of the MouseGrabber. */ void MouseGrabber::addInMouseGrabberPool() { - if (!isInMouseGrabberPool()) - MouseGrabber::MouseGrabberPool_.append(this); + if (!isInMouseGrabberPool()) + MouseGrabber::MouseGrabberPool_.append(this); } /*! Removes the MouseGrabber from the MouseGrabberPool(). @@ -60,12 +56,8 @@ See addInMouseGrabberPool() for details. Removing a MouseGrabber that is not in has no effect. */ void MouseGrabber::removeFromMouseGrabberPool() { - if (isInMouseGrabberPool()) -#if QT_VERSION >= 0x040000 - MouseGrabber::MouseGrabberPool_.removeAll(const_cast(this)); -#else - MouseGrabber::MouseGrabberPool_.removeRef(this); -#endif + if (isInMouseGrabberPool()) + MouseGrabber::MouseGrabberPool_.removeAll(const_cast(this)); } /*! Clears the MouseGrabberPool(). @@ -78,11 +70,7 @@ void MouseGrabber::removeFromMouseGrabberPool() (use this only if you're sure of what you do). */ void MouseGrabber::clearMouseGrabberPool(bool autoDelete) { -#if QT_VERSION >= 0x040000 - if (autoDelete) - qDeleteAll(MouseGrabber::MouseGrabberPool_); -#else - MouseGrabber::MouseGrabberPool_.setAutoDelete(autoDelete); -#endif - MouseGrabber::MouseGrabberPool_.clear(); + if (autoDelete) + qDeleteAll(MouseGrabber::MouseGrabberPool_); + MouseGrabber::MouseGrabberPool_.clear(); } diff --git a/octovis/src/extern/QGLViewer/mouseGrabber.h b/octovis/src/extern/QGLViewer/mouseGrabber.h index f08a91cd..e66a8b4e 100644 --- a/octovis/src/extern/QGLViewer/mouseGrabber.h +++ b/octovis/src/extern/QGLViewer/mouseGrabber.h @@ -1,8 +1,8 @@ /**************************************************************************** - Copyright (C) 2002-2013 Gilles Debunne. All rights reserved. + Copyright (C) 2002-2014 Gilles Debunne. All rights reserved. - This file is part of the QGLViewer library version 2.4.0. + This file is part of the QGLViewer library version 2.6.3. http://www.libqglviewer.com - contact@libqglviewer.com @@ -25,18 +25,14 @@ #include "config.h" -#if QT_VERSION >= 0x040000 -# include -#else -# include -#endif +#include class QGLViewer; namespace qglviewer { - class Camera; +class Camera; - /*! \brief Abstract class for objects that grab mouse focus in a QGLViewer. +/*! \brief Abstract class for objects that grab mouse focus in a QGLViewer. \class MouseGrabber mouseGrabber.h QGLViewer/mouseGrabber.h MouseGrabber are objects which react to the mouse cursor, usually when it hovers over them. This @@ -88,200 +84,180 @@ namespace qglviewer { class MovableObject : public MouseGrabber { public: - MovableObject() : pos(0,0), moved(false) {}; - - void checkIfGrabsMouse(int x, int y, const qglviewer::Camera* const) - { - // MovableObject is active in a region of 5 pixels around its pos. - // May depend on the actual shape of the object. Customize as desired. - // Once clicked (moved = true), it keeps grabbing mouse until button is released. - setGrabsMouse( moved || ((pos-QPoint(x,y)).manhattanLength() < 5) ); - } - - void mousePressEvent( QMouseEvent* const e, Camera* const) { prevPos = e->pos(); moved = true; } - - void mouseMoveEvent(QMouseEvent* const e, const Camera* const) - { - if (moved) - { - // Add position delta to current pos - pos += e->pos() - prevPos; - prevPos = e->pos(); - } - } - - void mouseReleaseEvent(QMouseEvent* const, Camera* const) { moved = false; } - - void draw() - { - // The object is drawn centered on its pos, with different possible aspects: - if (grabsMouse()) - if (moved) + MovableObject() : pos(0,0), moved(false) {} + + void checkIfGrabsMouse(int x, int y, const qglviewer::Camera* const) + { + // MovableObject is active in a region of 5 pixels around its pos. + // May depend on the actual shape of the object. Customize as desired. + // Once clicked (moved = true), it keeps grabbing mouse until button is released. + setGrabsMouse( moved || ((pos-QPoint(x,y)).manhattanLength() < 5) ); + } + + void mousePressEvent( QMouseEvent* const e, Camera* const) { prevPos = e->pos(); moved = true; } + + void mouseMoveEvent(QMouseEvent* const e, const Camera* const) + { + if (moved) + { + // Add position delta to current pos + pos += e->pos() - prevPos; + prevPos = e->pos(); + } + } + + void mouseReleaseEvent(QMouseEvent* const, Camera* const) { moved = false; } + + void draw() + { + // The object is drawn centered on its pos, with different possible aspects: + if (grabsMouse()) + if (moved) // Object being moved, maybe a transparent display - else + else // Object ready to be moved, maybe a highlighted visual feedback - else - // Normal display - } + else + // Normal display + } private: - QPoint pos, prevPos; - bool moved; + QPoint pos, prevPos; + bool moved; }; \endcode Note that the different event callback methods are called only once the MouseGrabber grabsMouse(). \nosubgrouping */ - class QGLVIEWER_EXPORT MouseGrabber - { +class QGLVIEWER_EXPORT MouseGrabber +{ #ifndef DOXYGEN - friend class ::QGLViewer; + friend class ::QGLViewer; #endif - public: - MouseGrabber(); - /*! Virtual destructor. Removes the MouseGrabber from the MouseGrabberPool(). */ -#if QT_VERSION >= 0x040000 - virtual ~MouseGrabber() { MouseGrabber::MouseGrabberPool_.removeAll(this); }; -#else - virtual ~MouseGrabber() { MouseGrabber::MouseGrabberPool_.removeRef(this); }; -#endif +public: + MouseGrabber(); + /*! Virtual destructor. Removes the MouseGrabber from the MouseGrabberPool(). */ + virtual ~MouseGrabber() { MouseGrabber::MouseGrabberPool_.removeAll(this); } - /*! @name Mouse grabbing detection */ - //@{ - public: - /*! Pure virtual method, called by the QGLViewers before they test if the MouseGrabber - grabsMouse(). Should setGrabsMouse() according to the mouse position. + /*! @name Mouse grabbing detection */ + //@{ +public: + /*! Pure virtual method, called by the QGLViewers before they test if the MouseGrabber + grabsMouse(). Should setGrabsMouse() according to the mouse position. - This is the core method of the MouseGrabber. It has to be overloaded in your derived class. - Its goal is to update the grabsMouse() flag according to the mouse and MouseGrabber current - positions, using setGrabsMouse(). + This is the core method of the MouseGrabber. It has to be overloaded in your derived class. + Its goal is to update the grabsMouse() flag according to the mouse and MouseGrabber current + positions, using setGrabsMouse(). - grabsMouse() is usually set to \c true when the mouse cursor is close enough to the MouseGrabber - position. It should also be set to \c false when the mouse cursor leaves this region in order to - release the mouse focus. + grabsMouse() is usually set to \c true when the mouse cursor is close enough to the MouseGrabber + position. It should also be set to \c false when the mouse cursor leaves this region in order to + release the mouse focus. + + \p x and \p y are the mouse cursor coordinates (Qt coordinate system: (0,0) corresponds to the upper + left corner). - \p x and \p y are the mouse cursor coordinates (Qt coordinate system: (0,0) corresponds to the upper - left corner). + A typical implementation will look like: + \code + // (posX,posY) is the position of the MouseGrabber on screen. + // Here, distance to mouse must be less than 10 pixels to activate the MouseGrabber. + setGrabsMouse( sqrt((x-posX)*(x-posX) + (y-posY)*(y-posY)) < 10); + \endcode - A typical implementation will look like: - \code - // (posX,posY) is the position of the MouseGrabber on screen. - // Here, distance to mouse must be less than 10 pixels to activate the MouseGrabber. - setGrabsMouse( sqrt((x-posX)*(x-posX) + (y-posY)*(y-posY)) < 10); - \endcode + If the MouseGrabber position is defined in 3D, use the \p camera parameter, corresponding to + the calling QGLViewer Camera. Project on screen and then compare the projected coordinates: + \code + Vec proj = camera->projectedCoordinatesOf(myMouseGrabber->frame()->position()); + setGrabsMouse((fabs(x-proj.x) < 5) && (fabs(y-proj.y) < 2)); // Rectangular region + \endcode - If the MouseGrabber position is defined in 3D, use the \p camera parameter, corresponding to - the calling QGLViewer Camera. Project on screen and then compare the projected coordinates: - \code - Vec proj = camera->projectedCoordinatesOf(myMouseGrabber->frame()->position()); - setGrabsMouse((fabs(x-proj.x) < 5) && (fabs(y-proj.y) < 2)); // Rectangular region - \endcode + See examples in the detailed description section and in the mouseGrabber example. */ + virtual void checkIfGrabsMouse(int x, int y, const Camera* const camera) = 0; - See examples in the detailed description section and in the mouseGrabber example. */ - virtual void checkIfGrabsMouse(int x, int y, const Camera* const camera) = 0; + /*! Returns \c true when the MouseGrabber grabs the QGLViewer's mouse events. - /*! Returns \c true when the MouseGrabber grabs the QGLViewer's mouse events. + This flag is set with setGrabsMouse() by the checkIfGrabsMouse() method. */ + bool grabsMouse() const { return grabsMouse_; } - This flag is set with setGrabsMouse() by the checkIfGrabsMouse() method. */ - bool grabsMouse() const { return grabsMouse_; }; +protected: + /*! Sets the grabsMouse() flag. Normally used by checkIfGrabsMouse(). */ + void setGrabsMouse(bool grabs) { grabsMouse_ = grabs; } + //@} - protected: - /*! Sets the grabsMouse() flag. Normally used by checkIfGrabsMouse(). */ - void setGrabsMouse(bool grabs) { grabsMouse_ = grabs; }; - //@} + /*! @name MouseGrabber pool */ + //@{ +public: + /*! Returns a list containing pointers to all the active MouseGrabbers. - /*! @name MouseGrabber pool */ - //@{ - public: - /*! Returns a list containing pointers to all the active MouseGrabbers. - - Used by the QGLViewer to parse all the MouseGrabbers and to check if any of them grabsMouse() - using checkIfGrabsMouse(). - - You should not have to directly use this list. Use removeFromMouseGrabberPool() and - addInMouseGrabberPool() to modify this list. - - \attention This method returns a \c QPtrList with Qt 3 and a \c QList with Qt 2. */ -#if QT_VERSION >= 0x040000 - static const QList& MouseGrabberPool() { return MouseGrabber::MouseGrabberPool_; }; -#else -# if QT_VERSION >= 0x030000 - static const QPtrList& MouseGrabberPool() { return MouseGrabber::MouseGrabberPool_; }; -# else - static const QList& MouseGrabberPool() { return MouseGrabber::MouseGrabberPool_; }; -# endif -#endif + Used by the QGLViewer to parse all the MouseGrabbers and to check if any of them grabsMouse() + using checkIfGrabsMouse(). - /*! Returns \c true if the MouseGrabber is currently in the MouseGrabberPool() list. + You should not have to directly use this list. Use removeFromMouseGrabberPool() and + addInMouseGrabberPool() to modify this list. - Default value is \c true. When set to \c false using removeFromMouseGrabberPool(), the - QGLViewers no longer checkIfGrabsMouse() on this MouseGrabber. Use addInMouseGrabberPool() to - insert it back. */ -#if QT_VERSION >= 0x040000 - bool isInMouseGrabberPool() const { return MouseGrabber::MouseGrabberPool_.contains(const_cast(this)); }; -#else - bool isInMouseGrabberPool() const { return MouseGrabber::MouseGrabberPool_.findRef(this) != -1; }; -#endif - void addInMouseGrabberPool(); - void removeFromMouseGrabberPool(); - void clearMouseGrabberPool(bool autoDelete=false); - //@} + \attention This method returns a \c QPtrList with Qt 3 and a \c QList with Qt 2. */ + static const QList& MouseGrabberPool() { return MouseGrabber::MouseGrabberPool_; } + /*! Returns \c true if the MouseGrabber is currently in the MouseGrabberPool() list. - /*! @name Mouse event handlers */ - //@{ - protected: - /*! Callback method called when the MouseGrabber grabsMouse() and a mouse button is pressed. + Default value is \c true. When set to \c false using removeFromMouseGrabberPool(), the + QGLViewers no longer checkIfGrabsMouse() on this MouseGrabber. Use addInMouseGrabberPool() to + insert it back. */ + bool isInMouseGrabberPool() const { return MouseGrabber::MouseGrabberPool_.contains(const_cast(this)); } + void addInMouseGrabberPool(); + void removeFromMouseGrabberPool(); + void clearMouseGrabberPool(bool autoDelete=false); + //@} - The MouseGrabber will typically start an action or change its state when a mouse button is - pressed. mouseMoveEvent() (called at each mouse displacement) will then update the MouseGrabber - accordingly and mouseReleaseEvent() (called when the mouse button is released) will terminate - this action. + /*! @name Mouse event handlers */ + //@{ +protected: + /*! Callback method called when the MouseGrabber grabsMouse() and a mouse button is pressed. - Use the \p event QMouseEvent::state() and QMouseEvent::button() to test the keyboard - and button state and possibly change the MouseGrabber behavior accordingly. - See the detailed description section and the mouseGrabber example for examples. + The MouseGrabber will typically start an action or change its state when a mouse button is + pressed. mouseMoveEvent() (called at each mouse displacement) will then update the MouseGrabber + accordingly and mouseReleaseEvent() (called when the mouse button is released) will terminate + this action. - See the \c QGLWidget::mousePressEvent() and the \c QMouseEvent documentations for details. */ - virtual void mousePressEvent(QMouseEvent* const event, Camera* const camera) { Q_UNUSED(event) Q_UNUSED(camera) }; - /*! Callback method called when the MouseGrabber grabsMouse() and a mouse button is double clicked. + Use the \p event QMouseEvent::state() and QMouseEvent::button() to test the keyboard + and button state and possibly change the MouseGrabber behavior accordingly. - See the \c QGLWidget::mouseDoubleClickEvent() and the \c QMouseEvent documentations for details. */ - virtual void mouseDoubleClickEvent(QMouseEvent* const event, Camera* const camera) { Q_UNUSED(event) Q_UNUSED(camera) }; - /*! Mouse release event callback method. See mousePressEvent(). */ - virtual void mouseReleaseEvent(QMouseEvent* const event, Camera* const camera) { Q_UNUSED(event) Q_UNUSED(camera) }; - /*! Callback method called when the MouseGrabber grabsMouse() and the mouse is moved while a - button is pressed. + See the detailed description section and the mouseGrabber example for examples. - This method will typically update the state of the MouseGrabber from the mouse displacement. See - the mousePressEvent() documentation for details. */ - virtual void mouseMoveEvent(QMouseEvent* const event, Camera* const camera) { Q_UNUSED(event) Q_UNUSED(camera) }; - /*! Callback method called when the MouseGrabber grabsMouse() and the mouse wheel is used. + See the \c QGLWidget::mousePressEvent() and the \c QMouseEvent documentations for details. */ + virtual void mousePressEvent(QMouseEvent* const event, Camera* const camera) { Q_UNUSED(event); Q_UNUSED(camera); } + /*! Callback method called when the MouseGrabber grabsMouse() and a mouse button is double clicked. - See the \c QGLWidget::wheelEvent() and the \c QWheelEvent documentations for details. */ - virtual void wheelEvent(QWheelEvent* const event, Camera* const camera) { Q_UNUSED(event) Q_UNUSED(camera) }; - //@} + See the \c QGLWidget::mouseDoubleClickEvent() and the \c QMouseEvent documentations for details. */ + virtual void mouseDoubleClickEvent(QMouseEvent* const event, Camera* const camera) { Q_UNUSED(event); Q_UNUSED(camera); } + /*! Mouse release event callback method. See mousePressEvent(). */ + virtual void mouseReleaseEvent(QMouseEvent* const event, Camera* const camera) { Q_UNUSED(event); Q_UNUSED(camera); } + /*! Callback method called when the MouseGrabber grabsMouse() and the mouse is moved while a + button is pressed. - private: - // Copy constructor and opertor= are declared private and undefined - // Prevents everyone from trying to use them - MouseGrabber(const MouseGrabber&); - MouseGrabber& operator=(const MouseGrabber&); - - bool grabsMouse_; - - // Q G L V i e w e r p o o l -#if QT_VERSION >= 0x040000 - static QList MouseGrabberPool_; -#else - static QPtrList MouseGrabberPool_; -#endif - }; + This method will typically update the state of the MouseGrabber from the mouse displacement. See + the mousePressEvent() documentation for details. */ + virtual void mouseMoveEvent(QMouseEvent* const event, Camera* const camera) { Q_UNUSED(event); Q_UNUSED(camera); } + /*! Callback method called when the MouseGrabber grabsMouse() and the mouse wheel is used. + + See the \c QGLWidget::wheelEvent() and the \c QWheelEvent documentations for details. */ + virtual void wheelEvent(QWheelEvent* const event, Camera* const camera) { Q_UNUSED(event); Q_UNUSED(camera); } + //@} + +private: + // Copy constructor and opertor= are declared private and undefined + // Prevents everyone from trying to use them + MouseGrabber(const MouseGrabber&); + MouseGrabber& operator=(const MouseGrabber&); + + bool grabsMouse_; + + // Q G L V i e w e r p o o l + static QList MouseGrabberPool_; +}; } // namespace qglviewer diff --git a/octovis/src/extern/QGLViewer/qglviewer.cpp b/octovis/src/extern/QGLViewer/qglviewer.cpp index 6dce7551..542545c0 100644 --- a/octovis/src/extern/QGLViewer/qglviewer.cpp +++ b/octovis/src/extern/QGLViewer/qglviewer.cpp @@ -1,8 +1,8 @@ /**************************************************************************** - Copyright (C) 2002-2013 Gilles Debunne. All rights reserved. + Copyright (C) 2002-2014 Gilles Debunne. All rights reserved. - This file is part of the QGLViewer library version 2.4.0. + This file is part of the QGLViewer library version 2.6.3. http://www.libqglviewer.com - contact@libqglviewer.com @@ -24,8 +24,8 @@ #include "qglviewer.h" #include "camera.h" #include "keyFrameInterpolator.h" +#include "manipulatedCameraFrame.h" -#if QT_VERSION >= 0x040000 # include # include # include @@ -40,34 +40,12 @@ # include # include # include -#else -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include - // Patch for enums names change -# define KeyboardModifierMask KeyButtonMask - // Patch for QMap API change -# define value data -#endif using namespace std; using namespace qglviewer; // Static private variable -#if QT_VERSION >= 0x040000 QList QGLViewer::QGLViewerPool_; -#else -QPtrList QGLViewer::QGLViewerPool_; -#endif /*! \mainpage @@ -89,29 +67,17 @@ See the project main page for details on the project and installation steps. */ void QGLViewer::defaultConstructor() { - // - - - W A R N I N G - - - - // This method should not call initializeGL(). Otherwise, as we are in the - // base class constructor, the user-defined init() would never be called. - // The different QGLViewer::setXXX are hence protected, so that updateGL is not called. - // The different constructor code should then be EMPTY. - updateGLOK_ = false; - // Test OpenGL context // if (glGetString(GL_VERSION) == 0) // qWarning("Unable to get OpenGL version, context may not be available - Check your configuration"); -#if QT_VERSION >= 0x040000 int poolIndex = QGLViewer::QGLViewerPool_.indexOf(NULL); setFocusPolicy(Qt::StrongFocus); -#else - int poolIndex = QGLViewer::QGLViewerPool_.findRef(NULL); - setFocusPolicy(QWidget::StrongFocus); -#endif - if (poolIndex >= 0) - QGLViewer::QGLViewerPool_.replace(poolIndex, this); - else - QGLViewer::QGLViewerPool_.append(this); + if (poolIndex >= 0) + QGLViewer::QGLViewerPool_.replace(poolIndex, this); + else + QGLViewer::QGLViewerPool_.append(this); camera_ = new Camera(); setCamera(camera()); @@ -130,7 +96,8 @@ void QGLViewer::defaultConstructor() fpsString_ = tr("%1Hz", "Frames per seconds, in Hertz").arg("?"); visualHint_ = 0; previousPathId_ = 0; - // prevPos_ is not initialized since pos() is not meaningful here. It will be set by setFullScreen(). + // prevPos_ is not initialized since pos() is not meaningful here. + // It will be set when setFullScreen(false) is called after setFullScreen(true) // #CONNECTION# default values in initFromDOMElement() manipulatedFrame_ = NULL; @@ -139,9 +106,7 @@ void QGLViewer::defaultConstructor() mouseGrabberIsAManipulatedCameraFrame_ = false; displayMessage_ = false; connect(&messageTimer_, SIGNAL(timeout()), SLOT(hideMessage())); -#if QT_VERSION >= 0x040000 messageTimer_.setSingleShot(true); -#endif helpWidget_ = NULL; setMouseGrabber(NULL); @@ -156,6 +121,8 @@ void QGLViewer::defaultConstructor() setCameraIsEdited(false); setTextIsEnabled(true); setStereoDisplay(false); + // Make sure move() is not called, which would call initializeGL() + fullScreen_ = false; setFullScreen(false); animationTimerId_ = 0; @@ -175,15 +142,14 @@ void QGLViewer::defaultConstructor() bufferTextureHeight_ = 0; previousBufferTextureFormat_ = 0; previousBufferTextureInternalFormat_ = 0; + currentlyPressedKey_ = Qt::Key(0); -#if QT_VERSION >= 0x040000 setAttribute(Qt::WA_NoSystemBackground); -#endif tileRegion_ = NULL; } -#if QT_VERSION >= 0x040000 && !defined QT3_SUPPORT +#if !defined QT3_SUPPORT /*! Constructor. See \c QGLWidget documentation for details. All viewer parameters (display flags, scene parameters, associated objects...) are set to their default values. See @@ -192,16 +158,13 @@ the associated documentation. If the \p shareWidget parameter points to a valid \c QGLWidget, the QGLViewer will share the OpenGL context with \p shareWidget (see isSharing()). */ QGLViewer::QGLViewer(QWidget* parent, const QGLWidget* shareWidget, Qt::WindowFlags flags) -: QGLWidget(parent, shareWidget, flags) + : QGLWidget(parent, shareWidget, flags) { defaultConstructor(); } /*! Same as QGLViewer(), but a \c QGLContext can be provided so that viewers share GL contexts, even -with \c QGLContext sub-classes (use \p shareWidget otherwise). - -\note This constructor is correctly working only with Qt versions greater or equal than 3.2. The -provided \p context is simply ignored otherwise. */ +with \c QGLContext sub-classes (use \p shareWidget otherwise). */ QGLViewer::QGLViewer(QGLContext *context, QWidget* parent, const QGLWidget* shareWidget, Qt::WindowFlags flags) -: QGLWidget(context, parent, shareWidget, flags) + : QGLWidget(context, parent, shareWidget, flags) { defaultConstructor(); } /*! Same as QGLViewer(), but a specific \c QGLFormat can be provided. @@ -209,13 +172,13 @@ QGLViewer::QGLViewer(QGLContext *context, QWidget* parent, const QGLWidget* shar This is for instance needed to ask for a stencil buffer or for stereo display (as is illustrated in the stereoViewer example). */ QGLViewer::QGLViewer(const QGLFormat& format, QWidget* parent, const QGLWidget* shareWidget, Qt::WindowFlags flags) -: QGLWidget(format, parent, shareWidget, flags) + : QGLWidget(format, parent, shareWidget, flags) { defaultConstructor(); } -#endif +#endif // QT3_SUPPORT /*! Virtual destructor. -The viewer is replaced by \c NULL in the QGLViewerPool() (in order to preserve other viewer's indexes) and allocated +The viewer is replaced by \c NULL in the QGLViewerPool() (in order to preserve other viewer's indexes) and allocated memory is released. The camera() is deleted and should be copied before if it is shared by an other viewer. */ QGLViewer::~QGLViewer() { @@ -224,11 +187,7 @@ QGLViewer::~QGLViewer() // if (parent()) // saveStateToFileForAllViewers(); -#if QT_VERSION >= 0x040000 QGLViewer::QGLViewerPool_.replace(QGLViewer::QGLViewerPool_.indexOf(this), NULL); -#else - QGLViewer::QGLViewerPool_.replace(QGLViewer::QGLViewerPool_.findRef(this), NULL); -#endif delete camera(); delete[] selectBuffer_; @@ -244,53 +203,19 @@ QGLViewer::~QGLViewer() static QString QGLViewerVersionString() { return QString::number((QGLVIEWER_VERSION & 0xff0000) >> 16) + "." + - QString::number((QGLVIEWER_VERSION & 0x00ff00) >> 8) + "." + - QString::number(QGLVIEWER_VERSION & 0x0000ff); + QString::number((QGLVIEWER_VERSION & 0x00ff00) >> 8) + "." + + QString::number(QGLVIEWER_VERSION & 0x0000ff); } -static int convertToKeyboardModifiers(int state) -{ -#if QT_VERSION < 0x040000 - // Qt 2 & 3 have different values for ButtonState and Modifiers. - // Converts CTRL,SHIFT... to ControlButton, ShiftButton... - if (state & Qt::MODIFIER_MASK) - { - if (state & Qt::CTRL) { state &= ~Qt::CTRL; state |= Qt::ControlButton; } - if (state & Qt::SHIFT) { state &= ~Qt::SHIFT; state |= Qt::ShiftButton; } - if (state & Qt::ALT) { state &= ~Qt::ALT; state |= Qt::AltButton; } -# if QT_VERSION >= 0x030100 - if (state & Qt::META) { state &= ~Qt::META; state |= Qt::MetaButton; } -# endif - } -#endif - return state; +static Qt::KeyboardModifiers keyboardModifiersFromState(unsigned int state) { + // Convertion of keyboard modifiers and mouse buttons as an int is no longer supported : emulate + return Qt::KeyboardModifiers(int(state & 0xFF000000)); } -static Qt::KeyboardModifiers convertKeyboardModifiers(Qt::KeyboardModifiers modifiers) -{ -#if QT_VERSION < 0x040000 - return Qt::KeyboardModifiers(convertToKeyboardModifiers(modifiers)); -#else - return modifiers; -#endif -} -static int convertToShortModifier(int state) -{ - // Converts ControlButton, ShiftButton... to CTRL,SHIFT... - // convertToKeyboardModifiers does the opposite -#if QT_VERSION < 0x040000 - if (state & Qt::KeyButtonMask) - { - if (state & Qt::ControlButton) { state &= ~Qt::ControlButton; state |= Qt::CTRL; } - if (state & Qt::ShiftButton) { state &= ~Qt::ShiftButton; state |= Qt::SHIFT; } - if (state & Qt::AltButton) { state &= ~Qt::AltButton; state |= Qt::ALT; } -# if QT_VERSION >= 0x030100 - if (state & Qt::MetaButton) { state &= ~Qt::MetaButton; state |= Qt::META; } -# endif - } -#endif - return state; +static Qt::MouseButton mouseButtonFromState(unsigned int state) { + // Convertion of keyboard modifiers and mouse buttons as an int is no longer supported : emulate + return Qt::MouseButton(state & 0xFFFF); } /*! Initializes the QGLViewer OpenGL context and then calls user-defined init(). @@ -313,9 +238,6 @@ If you port an existing application to QGLViewer and your display changes, you p disable these flags in init() to get back to a standard OpenGL state. */ void QGLViewer::initializeGL() { - if (updateGLOK_) - qWarning("Internal debug: initializeGL() is called in QGLViewer constructor."); - glEnable(GL_LIGHT0); glEnable(GL_LIGHTING); glEnable(GL_DEPTH_TEST); @@ -342,8 +264,6 @@ void QGLViewer::initializeGL() // Give time to glInit to finish and then call setFullScreen(). if (isFullScreen()) QTimer::singleShot( 100, this, SLOT(delayedFullScreen()) ); - - updateGLOK_ = true; } /*! Main paint method, inherited from \c QGLWidget. @@ -354,7 +274,6 @@ Calls the following methods, in that order: \arg postDraw() : display of visual hints (world axis, FPS...) */ void QGLViewer::paintGL() { - updateGLOK_ = false; if (displaysInStereo()) { for (int view=1; view>=0; --view) @@ -381,7 +300,6 @@ void QGLViewer::paintGL() // Add visual hints: axis, camera, grid... postDraw(); } - updateGLOK_ = true; Q_EMIT drawFinished(true); } @@ -451,7 +369,7 @@ void QGLViewer::postDraw() if (cameraIsEdited()) camera()->drawAllPaths(); - // Revolve Around Point, line when camera rolls, zoom region + // Pivot point, line when camera rolls, zoom region drawVisualHints(); if (gridIsDrawn()) { glLineWidth(1.0); drawGrid(camera()->sceneRadius()); } @@ -468,10 +386,10 @@ void QGLViewer::postDraw() // Restore foregroundColor float color[4]; - color[0] = foregroundColor().red() / 255.0; - color[1] = foregroundColor().green() / 255.0; - color[2] = foregroundColor().blue() / 255.0; - color[3] = 1.0; + color[0] = foregroundColor().red() / 255.0f; + color[1] = foregroundColor().green() / 255.0f; + color[2] = foregroundColor().blue() / 255.0f; + color[3] = 1.0f; glMaterialfv(GL_FRONT_AND_BACK, GL_AMBIENT_AND_DIFFUSE, color); glDisable(GL_LIGHTING); glDisable(GL_DEPTH_TEST); @@ -542,40 +460,39 @@ void QGLViewer::setCameraIsEdited(bool edit) Q_EMIT cameraIsEditedChanged(edit); - if (updateGLOK_) - updateGL(); + update(); } // Key bindings. 0 means not defined void QGLViewer::setDefaultShortcuts() { // D e f a u l t a c c e l e r a t o r s - setShortcut(DRAW_AXIS, Qt::Key_A); - setShortcut(DRAW_GRID, Qt::Key_G); - setShortcut(DISPLAY_FPS, Qt::Key_F); - setShortcut(ENABLE_TEXT, Qt::SHIFT+Qt::Key_Question); - setShortcut(EXIT_VIEWER, Qt::Key_Escape); - setShortcut(SAVE_SCREENSHOT, Qt::CTRL+Qt::Key_S); - setShortcut(CAMERA_MODE, Qt::Key_Space); - setShortcut(FULL_SCREEN, Qt::ALT+Qt::Key_Return); - setShortcut(STEREO, Qt::Key_S); - setShortcut(ANIMATION, Qt::Key_Return); - setShortcut(HELP, Qt::Key_H); - setShortcut(EDIT_CAMERA, Qt::Key_C); - setShortcut(MOVE_CAMERA_LEFT, Qt::Key_Left); + setShortcut(DRAW_AXIS, Qt::Key_A); + setShortcut(DRAW_GRID, Qt::Key_G); + setShortcut(DISPLAY_FPS, Qt::Key_F); + setShortcut(ENABLE_TEXT, Qt::SHIFT+Qt::Key_Question); + setShortcut(EXIT_VIEWER, Qt::Key_Escape); + setShortcut(SAVE_SCREENSHOT, Qt::CTRL+Qt::Key_S); + setShortcut(CAMERA_MODE, Qt::Key_Space); + setShortcut(FULL_SCREEN, Qt::ALT+Qt::Key_Return); + setShortcut(STEREO, Qt::Key_S); + setShortcut(ANIMATION, Qt::Key_Return); + setShortcut(HELP, Qt::Key_H); + setShortcut(EDIT_CAMERA, Qt::Key_C); + setShortcut(MOVE_CAMERA_LEFT, Qt::Key_Left); setShortcut(MOVE_CAMERA_RIGHT,Qt::Key_Right); - setShortcut(MOVE_CAMERA_UP, Qt::Key_Up); - setShortcut(MOVE_CAMERA_DOWN, Qt::Key_Down); - setShortcut(INCREASE_FLYSPEED,Qt::Key_Plus); - setShortcut(DECREASE_FLYSPEED,Qt::Key_Minus); - setShortcut(SNAPSHOT_TO_CLIPBOARD,Qt::CTRL+Qt::Key_C); + setShortcut(MOVE_CAMERA_UP, Qt::Key_Up); + setShortcut(MOVE_CAMERA_DOWN, Qt::Key_Down); + setShortcut(INCREASE_FLYSPEED, Qt::Key_Plus); + setShortcut(DECREASE_FLYSPEED, Qt::Key_Minus); + setShortcut(SNAPSHOT_TO_CLIPBOARD, Qt::CTRL+Qt::Key_C); keyboardActionDescription_[DISPLAY_FPS] = tr("Toggles the display of the FPS", "DISPLAY_FPS action description"); keyboardActionDescription_[SAVE_SCREENSHOT] = tr("Saves a screenshot", "SAVE_SCREENSHOT action description"); keyboardActionDescription_[FULL_SCREEN] = tr("Toggles full screen display", "FULL_SCREEN action description"); keyboardActionDescription_[DRAW_AXIS] = tr("Toggles the display of the world axis", "DRAW_AXIS action description"); keyboardActionDescription_[DRAW_GRID] = tr("Toggles the display of the XY grid", "DRAW_GRID action description"); - keyboardActionDescription_[CAMERA_MODE] = tr("Changes camera mode (revolve or fly)", "CAMERA_MODE action description"); + keyboardActionDescription_[CAMERA_MODE] = tr("Changes camera mode (observe or fly)", "CAMERA_MODE action description"); keyboardActionDescription_[STEREO] = tr("Toggles stereo display", "STEREO action description"); keyboardActionDescription_[HELP] = tr("Opens this help window", "HELP action description"); keyboardActionDescription_[ANIMATION] = tr("Starts/stops the animation", "ANIMATION action description"); @@ -604,87 +521,63 @@ void QGLViewer::setDefaultShortcuts() setPathKey(Qt::Key_F11, 11); setPathKey(Qt::Key_F12, 12); -#if QT_VERSION >= 0x040000 setAddKeyFrameKeyboardModifiers(Qt::AltModifier); setPlayPathKeyboardModifiers(Qt::NoModifier); -#else - setAddKeyFrameKeyboardModifiers(Qt::AltButton); - setPlayPathKeyboardModifiers(Qt::NoButton); -#endif } // M o u s e b e h a v i o r void QGLViewer::setDefaultMouseBindings() { -#if QT_VERSION >= 0x040000 - const Qt::KeyboardModifiers cameraKeyboardModifiers = Qt::NoModifier; - const Qt::KeyboardModifiers frameKeyboardModifiers = Qt::ControlModifier; -#else - const Qt::KeyboardModifiers cameraKeyboardModifiers = Qt::NoButton; - const Qt::KeyboardModifiers frameKeyboardModifiers = Qt::ControlButton; -#endif + const Qt::KeyboardModifiers cameraKeyboardModifiers = Qt::NoModifier; + const Qt::KeyboardModifiers frameKeyboardModifiers = Qt::ControlModifier; + //#CONNECTION# toggleCameraMode() for (int handler=0; handler<2; ++handler) { MouseHandler mh = (MouseHandler)(handler); - Qt::KeyboardModifiers modifiers = (mh == FRAME) ? frameKeyboardModifiers : cameraKeyboardModifiers; - - setMouseBinding(modifiers | Qt::LeftButton, mh, ROTATE); - setMouseBinding(modifiers | Qt::MidButton, mh, ZOOM); - setMouseBinding(modifiers | Qt::RightButton, mh, TRANSLATE); + Qt::KeyboardModifiers modifiers = (mh == FRAME) ? frameKeyboardModifiers : cameraKeyboardModifiers; - setMouseBinding(modifiers | Qt::LeftButton | Qt::MidButton, mh, SCREEN_ROTATE); - // 2.2.4 setMouseBinding(modifiers | Qt::RightButton | Qt::MidButton, mh, SCREEN_TRANSLATE); + setMouseBinding(modifiers, Qt::LeftButton, mh, ROTATE); + setMouseBinding(modifiers, Qt::MidButton, mh, ZOOM); + setMouseBinding(modifiers, Qt::RightButton, mh, TRANSLATE); + + setMouseBinding(Qt::Key_R, modifiers, Qt::LeftButton, mh, SCREEN_ROTATE); setWheelBinding(modifiers, mh, ZOOM); } -#if QT_VERSION >= 0x040000 // Z o o m o n r e g i o n - setMouseBinding(Qt::SHIFT + Qt::MidButton, CAMERA, ZOOM_ON_REGION); + setMouseBinding(Qt::ShiftModifier, Qt::MidButton, CAMERA, ZOOM_ON_REGION); + // S e l e c t - setMouseBinding(Qt::SHIFT + Qt::LeftButton, SELECT); -#else - setMouseBinding(Qt::SHIFT + Qt::MidButton, CAMERA, ZOOM_ON_REGION); - setMouseBinding(Qt::SHIFT + Qt::LeftButton, SELECT); -#endif + setMouseBinding(Qt::ShiftModifier, Qt::LeftButton, SELECT); + setMouseBinding(Qt::ShiftModifier, Qt::RightButton, RAP_FROM_PIXEL); // D o u b l e c l i c k - setMouseBinding(Qt::LeftButton, ALIGN_CAMERA, true); - setMouseBinding(Qt::MidButton, SHOW_ENTIRE_SCENE, true); - setMouseBinding(Qt::RightButton, CENTER_SCENE, true); + setMouseBinding(Qt::NoModifier, Qt::LeftButton, ALIGN_CAMERA, true); + setMouseBinding(Qt::NoModifier, Qt::MidButton, SHOW_ENTIRE_SCENE, true); + setMouseBinding(Qt::NoModifier, Qt::RightButton, CENTER_SCENE, true); - setMouseBinding(frameKeyboardModifiers | Qt::LeftButton, ALIGN_FRAME, true); - setMouseBinding(frameKeyboardModifiers | Qt::RightButton, CENTER_FRAME, true); + setMouseBinding(frameKeyboardModifiers, Qt::LeftButton, ALIGN_FRAME, true); + // middle double click makes no sense for manipulated frame + setMouseBinding(frameKeyboardModifiers, Qt::RightButton, CENTER_FRAME, true); - // S p e c i f i c d o u b l e c l i c k s - setMouseBinding(Qt::LeftButton, RAP_FROM_PIXEL, true, Qt::RightButton); - setMouseBinding(Qt::RightButton, RAP_IS_CENTER, true, Qt::LeftButton); - setMouseBinding(Qt::LeftButton, ZOOM_ON_PIXEL, true, Qt::MidButton); - setMouseBinding(Qt::RightButton, ZOOM_TO_FIT, true, Qt::MidButton); + // A c t i o n s w i t h k e y m o d i f i e r s + setMouseBinding(Qt::Key_Z, Qt::NoModifier, Qt::LeftButton, ZOOM_ON_PIXEL); + setMouseBinding(Qt::Key_Z, Qt::NoModifier, Qt::RightButton, ZOOM_TO_FIT); #ifdef Q_OS_MAC - // Specific Mac bindings. Double finger emulates a wheelEvent which zooms. - // Make Option + left emulate the right button. Other bindings should be changed accordingly. + // Specific Mac bindings for touchpads. Two fingers emulate a wheelEvent which zooms. + // There is no right button available : make Option key + left emulate the right button. + // A Control+Left indeed emulates a right click (OS X system configuration), but it does + // no seem to support dragging. // Done at the end to override previous settings. -# if QT_VERSION >= 0x040000 - const Qt::KeyboardModifiers macKeyboardModifiers = Qt::AltModifier; -# else - const Qt::KeyboardModifiers macKeyboardModifiers = Qt::AltButton; -# endif + const Qt::KeyboardModifiers macKeyboardModifiers = Qt::AltModifier; - setMouseBinding(macKeyboardModifiers | Qt::LeftButton, CAMERA, TRANSLATE); - setMouseBinding(macKeyboardModifiers | Qt::LeftButton, CENTER_SCENE, true); - setMouseBinding(frameKeyboardModifiers | macKeyboardModifiers | Qt::LeftButton, CENTER_FRAME, true); - setMouseBinding(frameKeyboardModifiers | macKeyboardModifiers | Qt::LeftButton, FRAME, TRANSLATE); - - // S p e c i f i c d o u b l e c l i c k s - // A single tap is actually seen as a left followed by a right button click. - setMouseBinding(Qt::META + Qt::RightButton, RAP_FROM_PIXEL, true, Qt::LeftButton); - setMouseBinding(Qt::SHIFT + Qt::META + Qt::RightButton, RAP_IS_CENTER, true, Qt::LeftButton); - // A tap with two fingers is actually considered a rightButton. - setMouseBinding(Qt::META + Qt::RightButton, ZOOM_ON_PIXEL, false); - setMouseBinding(Qt::SHIFT + Qt::MetaModifier | Qt::RightButton, ZOOM_TO_FIT, false); + setMouseBinding(macKeyboardModifiers, Qt::LeftButton, CAMERA, TRANSLATE); + setMouseBinding(macKeyboardModifiers, Qt::LeftButton, CENTER_SCENE, true); + setMouseBinding(frameKeyboardModifiers | macKeyboardModifiers, Qt::LeftButton, CENTER_FRAME, true); + setMouseBinding(frameKeyboardModifiers | macKeyboardModifiers, Qt::LeftButton, FRAME, TRANSLATE); #endif } @@ -702,7 +595,7 @@ the previous camera pointer in order to prevent memory leaks if needed. The sceneRadius() and sceneCenter() of \p camera are set to the \e current QGLViewer values. All the \p camera qglviewer::Camera::keyFrameInterpolator() -qglviewer::KeyFrameInterpolator::interpolated() signals are connected to the viewer updateGL() slot. +qglviewer::KeyFrameInterpolator::interpolated() signals are connected to the viewer update() slot. The connections with the previous viewer's camera are removed. */ void QGLViewer::setCamera(Camera* const camera) { @@ -711,15 +604,15 @@ void QGLViewer::setCamera(Camera* const camera) camera->setSceneRadius(sceneRadius()); camera->setSceneCenter(sceneCenter()); - camera->setScreenWidthAndHeight(width(),height()); + camera->setScreenWidthAndHeight(width(), height()); - // Disconnect current camera to this viewer. - disconnect(this->camera()->frame(), SIGNAL(manipulated()), this, SLOT(updateGL())); - disconnect(this->camera()->frame(), SIGNAL(spun()), this, SLOT(updateGL())); + // Disconnect current camera from this viewer. + disconnect(this->camera()->frame(), SIGNAL(manipulated()), this, SLOT(update())); + disconnect(this->camera()->frame(), SIGNAL(spun()), this, SLOT(update())); // Connect camera frame to this viewer. - connect(camera->frame(), SIGNAL(manipulated()), SLOT(updateGL())); - connect(camera->frame(), SIGNAL(spun()), SLOT(updateGL())); + connect(camera->frame(), SIGNAL(manipulated()), SLOT(update())); + connect(camera->frame(), SIGNAL(spun()), SLOT(update())); connectAllCameraKFIInterpolatedSignals(false); camera_ = camera; @@ -730,18 +623,18 @@ void QGLViewer::setCamera(Camera* const camera) void QGLViewer::connectAllCameraKFIInterpolatedSignals(bool connection) { - for (QMap::ConstIterator it = camera()->kfi_.begin(), end=camera()->kfi_.end(); it != end; ++it) + for (QMap::ConstIterator it = camera()->kfi_.begin(), end=camera()->kfi_.end(); it != end; ++it) { if (connection) - connect(camera()->keyFrameInterpolator(it.key()), SIGNAL(interpolated()), SLOT(updateGL())); + connect(camera()->keyFrameInterpolator(it.key()), SIGNAL(interpolated()), SLOT(update())); else - disconnect(camera()->keyFrameInterpolator(it.key()), SIGNAL(interpolated()), this, SLOT(updateGL())); + disconnect(camera()->keyFrameInterpolator(it.key()), SIGNAL(interpolated()), this, SLOT(update())); } if (connection) - connect(camera()->interpolationKfi_, SIGNAL(interpolated()), SLOT(updateGL())); + connect(camera()->interpolationKfi_, SIGNAL(interpolated()), SLOT(update())); else - disconnect(camera()->interpolationKfi_, SIGNAL(interpolated()), this, SLOT(updateGL())); + disconnect(camera()->interpolationKfi_, SIGNAL(interpolated()), this, SLOT(update())); } /*! Draws a representation of \p light. @@ -760,11 +653,11 @@ See the drawLight example for an illust \attention You need to enable \c GL_COLOR_MATERIAL before calling this method. \c glColor is set to the light diffuse color. */ -void QGLViewer::drawLight(GLenum light, float scale) const +void QGLViewer::drawLight(GLenum light, qreal scale) const { static GLUquadric* quadric = gluNewQuadric(); - const float length = sceneRadius() / 5.0 * scale; + const qreal length = sceneRadius() / 5.0 * scale; GLboolean lightIsOn; glGetBooleanv(light, &lightIsOn); @@ -805,7 +698,7 @@ void QGLViewer::drawLight(GLenum light, float scale) const Vec dir(pos[0], pos[1], pos[2]); dir.normalize(); Frame fr=Frame(camera()->cameraCoordinatesOf(4.0 * length * camera()->frame()->inverseTransformOf(dir)), - Quaternion(Vec(0,0,-1), dir)); + Quaternion(Vec(0,0,-1), dir)); glMultMatrixd(fr.matrix()); drawArrow(length); } @@ -836,7 +729,7 @@ conveniently remove all the displayed text with a single keyboard shortcut. See also displayMessage() to drawText() for only a short amount of time. -Use QGLWidget::renderText(x,y,z, text) instead (Qt version >= 3.1) if you want to draw a text located +Use QGLWidget::renderText(x,y,z, text) instead if you want to draw a text located at a specific 3D position instead of 2D screen coordinates (fixed size text, facing the camera). The \c GL_MODELVIEW and \c GL_PROJECTION matrices are not modified by this method. @@ -844,140 +737,19 @@ The \c GL_MODELVIEW and \c GL_PROJECTION matrices are not modified by this metho \attention This method uses display lists to render the characters, with an index that starts at 2000 by default (see the QGLWidget::renderText() documentation). If you use more than 2000 Display Lists, they may overlap with these. Directly use QGLWidget::renderText() in that case, with a -higher \c listBase parameter (or overload fontDisplayListBase with Qt4). - -\attention There is a problem with anti-aliased font with nVidia cards and Qt versions lower than -3.3. Until this version, the \p fnt parameter is not taken into account to prevent a crash. It is -replaced by a fixed font that should be compatible with the \c qtconfig anti-aliased font -configuration (disable this option otherwise). - -\note This method uses QGLWidget::renderText() if your Qt version is greater or equal to 3.1, -otherwise it uses (and requires) GLUT. When GLUT is used, only the \p fnt size attribute (set with -QFont::setPixelSize() or QFont::setPointSize()) is taken into account. Also note that in that case -each call to drawText() changes the camera projection matrix and restores it back (using -startScreenCoordinatesSystem() and stopScreenCoordinatesSystem()). If you call this method several -times and it slows down your frame rate, consider factorizing the context changes. */ +higher \c listBase parameter (or overload fontDisplayListBase).*/ void QGLViewer::drawText(int x, int y, const QString& text, const QFont& fnt) { if (!textIsEnabled()) return; -#if QT_VERSION < QGLVIEWER_QT_VERSION_WITHOUT_GLUT - const GLfloat font_scale = 119.05f - 33.33f; // see glutStrokeCharacter man page - - startScreenCoordinatesSystem(); - - // Anti-aliased characters - glPushAttrib(GL_ALL_ATTRIB_BITS); - glDisable(GL_LIGHTING); - glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); - glEnable(GL_BLEND); - glDisable(GL_DEPTH_TEST); - glEnable(GL_LINE_SMOOTH); - glLineWidth(1.0); - - glTranslatef((GLfloat)x, (GLfloat)y, 0.0); - const GLfloat scale = ((fnt.pixelSize()>0)?fnt.pixelSize():fnt.pointSize()) / font_scale; - glScalef(scale, -scale, scale); - - for (uint i=0; i= 0x030200 - newFont.setStyleStrategy(QFont::OpenGLCompatible); -# endif - newFont.setStyleHint(QFont::AnyStyle, QFont::PreferBitmap); - renderText(x, y, text, newFont); -# else if (tileRegion_ != NULL) { - renderText((x-tileRegion_->xMin) * width() / (tileRegion_->xMax - tileRegion_->xMin), - (y-tileRegion_->yMin) * height() / (tileRegion_->yMax - tileRegion_->yMin), text, scaledFont(fnt)); + renderText(int((x-tileRegion_->xMin) * width() / (tileRegion_->xMax - tileRegion_->xMin)), + int((y-tileRegion_->yMin) * height() / (tileRegion_->yMax - tileRegion_->yMin)), text, scaledFont(fnt)); } else - renderText(x, y, text, fnt); -# endif - -#endif + renderText(x, y, text, fnt); } -/* Similar to drawText(), but the text is handled as a classical 3D object of the scene. - -Although useful, this method is deprecated with recent Qt versions. Indeed, Qt renders text as -pixmaps that cannot be oriented. However, when GLUT is used instead of Qt (when your Qt version is -lower than 3.1, see drawText() documentation) orientated characters are possible and this method will work. - -\p pos and \p normal respectively represent the 3D coordinate of the text and the normal to the text -plane. They are expressed with respect to the \e current \c GL_MODELVIEW matrix. - -If you want your text to always face the camera (normal parallel to camera()->viewDirection), use -QGLWidget::renderText(x,y,z). - -See the draw3DText example for an illustration. */ -/* -void QGLViewer::draw3DText(const Vec& pos, const Vec& normal, const QString& text, GLfloat height) -{ -#if QT_VERSION < QGLVIEWER_QT_VERSION_WITHOUT_GLUT -if (!textIsEnabled()) -return; - -glMatrixMode(GL_MODELVIEW) ; -glPushMatrix() ; - -const GLfloat font_scale = (119.05f - 33.33f) / 8; // see glutStrokeCharacter man page -// const GLfloat font_scale = (119.05f - 33.33f) * 15.0f; // see glutStrokeCharacter man page - -static GLfloat lineWidth; -glGetFloatv(GL_LINE_WIDTH, &lineWidth); - -glTranslatef(pos.x, pos.y, pos.z); -glMultMatrixd(Quaternion(Vec(0.0, 0.0, 1.0), normal).matrix()); - -glLineWidth(2.0); - -glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); -glEnable(GL_BLEND); -glEnable(GL_LINE_SMOOTH); - -const GLfloat scale = height / font_scale; -glScalef(scale, scale, scale); - -for (uint i=0; i= 3.1."); -qWarning("Use QGLWidget::renderText() instead,"); -qWarning("or use the glut glutStrokeCharacter() method."); -displayed = true; -} - -Q_UNUSED(pos) -Q_UNUSED(normal) -Q_UNUSED(text) -Q_UNUSED(height) -#endif -} -*/ - /*! Briefly displays a message in the lower left corner of the widget. Convenient to provide feedback to the user. @@ -993,30 +765,23 @@ void QGLViewer::displayMessage(const QString& message, int delay) { message_ = message; displayMessage_ = true; -#if QT_VERSION >= 0x040000 // Was set to single shot in defaultConstructor. messageTimer_.start(delay); -#else - if (messageTimer_.isActive()) - messageTimer_.changeInterval(delay); - else - messageTimer_.start(delay, true); -#endif - if (textIsEnabled() && updateGLOK_) - updateGL(); + if (textIsEnabled()) + update(); } void QGLViewer::hideMessage() { displayMessage_ = false; if (textIsEnabled()) - updateGL(); + update(); } /*! Displays the averaged currentFPS() frame rate in the upper left corner of the widget. -updateGL() should be called in a loop in order to have a meaningful value (this is the case when +update() should be called in a loop in order to have a meaningful value (this is the case when you continuously move the camera using the mouse or when animationIsStarted()). setAnimationPeriod(0) to make this loop as fast as possible in order to reach and measure the maximum available frame rate. @@ -1065,15 +830,15 @@ void QGLViewer::startScreenCoordinatesSystem(bool upward) const glPushMatrix(); glLoadIdentity(); if (tileRegion_ != NULL) - if (upward) - glOrtho(tileRegion_->xMin, tileRegion_->xMax, tileRegion_->yMin, tileRegion_->yMax, 0.0, -1.0); - else - glOrtho(tileRegion_->xMin, tileRegion_->xMax, tileRegion_->yMax, tileRegion_->yMin, 0.0, -1.0); + if (upward) + glOrtho(tileRegion_->xMin, tileRegion_->xMax, tileRegion_->yMin, tileRegion_->yMax, 0.0, -1.0); + else + glOrtho(tileRegion_->xMin, tileRegion_->xMax, tileRegion_->yMax, tileRegion_->yMin, 0.0, -1.0); else - if (upward) - glOrtho(0, width(), 0, height(), 0.0, -1.0); - else - glOrtho(0, width(), height(), 0, 0.0, -1.0); + if (upward) + glOrtho(0, width(), 0, height(), 0.0, -1.0); + else + glOrtho(0, width(), height(), 0, 0.0, -1.0); glMatrixMode(GL_MODELVIEW); glPushMatrix(); @@ -1101,7 +866,7 @@ void QGLViewer::timerEvent(QTimerEvent *) if (animationIsStarted()) { animate(); - updateGL(); + update(); } } @@ -1323,12 +1088,12 @@ void QGLViewer::endSelection(const QPoint& point) // Of all the objects that were projected in the pick region, we select the closest one (zMin comparison). // This code needs to be modified if you use several stack levels. See glSelectBuffer() man page. GLuint zMin = (selectBuffer())[1]; - setSelectedName((selectBuffer())[3]); + setSelectedName(int((selectBuffer())[3])); for (int i=1; iinterpolateToZoomOnPixel(e->pos()); - break; - case ZOOM_TO_FIT : - camera()->interpolateToFitScene(); - break; - case SELECT : - select(e); - updateGL(); - break; - case RAP_FROM_PIXEL : - if (camera()->setRevolveAroundPointFromPixel(e->pos())) - { + case NO_CLICK_ACTION : + break; + case ZOOM_ON_PIXEL : + camera()->interpolateToZoomOnPixel(e->pos()); + break; + case ZOOM_TO_FIT : + camera()->interpolateToFitScene(); + break; + case SELECT : + select(e); + update(); + break; + case RAP_FROM_PIXEL : + if (! camera()->setPivotPointFromPixel(e->pos())) + camera()->setPivotPoint(sceneCenter()); setVisualHintsMask(1); - updateGL(); - } - break; - case RAP_IS_CENTER : - camera()->setRevolveAroundPoint(sceneCenter()); - setVisualHintsMask(1); - updateGL(); - break; - case CENTER_FRAME : - if (manipulatedFrame()) - manipulatedFrame()->projectOnLine(camera()->position(), camera()->viewDirection()); - break; - case CENTER_SCENE : - camera()->centerScene(); - break; - case SHOW_ENTIRE_SCENE : - camera()->showEntireScene(); - break; - case ALIGN_FRAME : - if (manipulatedFrame()) - manipulatedFrame()->alignWithFrame(camera()->frame()); - break; - case ALIGN_CAMERA : - camera()->frame()->alignWithFrame(NULL, true); - break; + update(); + break; + case RAP_IS_CENTER : + camera()->setPivotPoint(sceneCenter()); + setVisualHintsMask(1); + update(); + break; + case CENTER_FRAME : + if (manipulatedFrame()) + manipulatedFrame()->projectOnLine(camera()->position(), camera()->viewDirection()); + break; + case CENTER_SCENE : + camera()->centerScene(); + break; + case SHOW_ENTIRE_SCENE : + camera()->showEntireScene(); + break; + case ALIGN_FRAME : + if (manipulatedFrame()) + manipulatedFrame()->alignWithFrame(camera()->frame()); + break; + case ALIGN_CAMERA : + Frame * frame = new Frame(); + frame->setTranslation(camera()->pivotPoint()); + camera()->frame()->alignWithFrame(frame, true); + delete frame; + break; } } @@ -1415,31 +1192,17 @@ void QGLViewer::mousePressEvent(QMouseEvent* e) { //#CONNECTION# mouseDoubleClickEvent has the same structure //#CONNECTION# mouseString() concatenates bindings description in inverse order. - ClickActionPrivate cap; - cap.doubleClick = false; -#if QT_VERSION >= 0x040000 - cap.modifiers = e->modifiers(); - cap.button = e->button(); - cap.buttonsBefore = (Qt::MouseButtons)(e->buttons() & ~(e->button())); -#else - cap.modifiers = (Qt::KeyboardModifiers)(e->state() & Qt::KeyboardModifierMask); - cap.button = (Qt::MouseButtons)((e->stateAfter() & Qt::MouseButtonMask) & (~(e->state() & Qt::MouseButtonMask))); - cap.buttonsBefore = (Qt::MouseButtons)(e->state() & Qt::MouseButtonMask); -#endif + ClickBindingPrivate cbp(e->modifiers(), e->button(), false, (Qt::MouseButtons)(e->buttons() & ~(e->button())), currentlyPressedKey_); - if (clickBinding_.contains(cap)) - performClickAction(clickBinding_[cap], e); - else + if (clickBinding_.contains(cbp)) { + performClickAction(clickBinding_[cbp], e); + } else if (mouseGrabber()) { if (mouseGrabberIsAManipulatedFrame_) { - for (QMap::ConstIterator it=mouseBinding_.begin(), end=mouseBinding_.end(); it!=end; ++it) -#if QT_VERSION >= 0x040000 - if ((it.value().handler == FRAME) && ((it.key() & Qt::MouseButtonMask) == e->buttons())) -#else - if ((it.data().handler == FRAME) && ((it.key() & Qt::MouseButtonMask) == (e->stateAfter() & Qt::MouseButtonMask))) -#endif + for (QMap::ConstIterator it=mouseBinding_.begin(), end=mouseBinding_.end(); it!=end; ++it) + if ((it.value().handler == FRAME) && (it.key().button == e->button())) { ManipulatedFrame* mf = dynamic_cast(mouseGrabber()); if (mouseGrabberIsAManipulatedCameraFrame_) @@ -1457,50 +1220,44 @@ void QGLViewer::mousePressEvent(QMouseEvent* e) } else mouseGrabber()->mousePressEvent(e, camera()); - updateGL(); + update(); } else { //#CONNECTION# wheelEvent has the same structure -#if QT_VERSION >= 0x040000 - const int state = e->modifiers() | e->buttons(); -#else - const int state = e->stateAfter(); -#endif + const MouseBindingPrivate mbp(e->modifiers(), e->button(), currentlyPressedKey_); - if (mouseBinding_.contains(state)) + if (mouseBinding_.contains(mbp)) { - MouseActionPrivate map = mouseBinding_[state]; + MouseActionPrivate map = mouseBinding_[mbp]; switch (map.handler) { - case CAMERA : - camera()->frame()->startAction(map.action, map.withConstraint); - camera()->frame()->mousePressEvent(e, camera()); - break; - case FRAME : - if (manipulatedFrame()) - { - if (manipulatedFrameIsACamera_) - { - manipulatedFrame()->ManipulatedFrame::startAction(map.action, map.withConstraint); - manipulatedFrame()->ManipulatedFrame::mousePressEvent(e, camera()); - } - else + case CAMERA : + camera()->frame()->startAction(map.action, map.withConstraint); + camera()->frame()->mousePressEvent(e, camera()); + break; + case FRAME : + if (manipulatedFrame()) { - manipulatedFrame()->startAction(map.action, map.withConstraint); - manipulatedFrame()->mousePressEvent(e, camera()); + if (manipulatedFrameIsACamera_) + { + manipulatedFrame()->ManipulatedFrame::startAction(map.action, map.withConstraint); + manipulatedFrame()->ManipulatedFrame::mousePressEvent(e, camera()); + } + else + { + manipulatedFrame()->startAction(map.action, map.withConstraint); + manipulatedFrame()->mousePressEvent(e, camera()); + } } - } - break; + break; } if (map.action == SCREEN_ROTATE) // Display visual hint line - updateGL(); + update(); } -#if QT_VERSION >= 0x030000 else e->ignore(); -#endif } } @@ -1514,13 +1271,6 @@ If you want to define your own mouse behavior, do something like this: void Viewer::mousePressEvent(QMouseEvent* e) { -// Qt version 2 or 3 : use Qt::KeyButtonMask and Qt::MouseButtonMask to separate the modifiers -// (Qt::ControlButton/Qt::AltButton/Qt::ShiftButton/Qt::MetaButton) from the mouse buttons -// (Qt::LeftButton/Qt::MidButton/Qt::RightButton) in state(). -if ( ((e->state() & Qt::KeyButtonMask) == myModifiers) && -((e->state() & Qt::MouseButtonMask) == myButton) ) - -// With Qt 4, use instead : if ((e->button() == myButton) && (e->modifiers() == myModifiers)) myMouseBehavior = true; else @@ -1555,7 +1305,7 @@ void QGLViewer::mouseMoveEvent(QMouseEvent* e) mouseGrabber()->mouseMoveEvent(e, camera()); else setMouseGrabber(NULL); - updateGL(); + update(); } if (!mouseGrabber()) @@ -1566,7 +1316,7 @@ void QGLViewer::mouseMoveEvent(QMouseEvent* e) camera()->frame()->mouseMoveEvent(e, camera()); // #CONNECTION# manipulatedCameraFrame::mouseMoveEvent specific if at the beginning if (camera()->frame()->action_ == ZOOM_ON_REGION) - updateGL(); + update(); } else // ! if ((manipulatedFrame()) && (manipulatedFrame()->isManipulated())) @@ -1577,14 +1327,8 @@ void QGLViewer::mouseMoveEvent(QMouseEvent* e) else if (hasMouseTracking()) { -#if QT_VERSION >= 0x040000 Q_FOREACH (MouseGrabber* mg, MouseGrabber::MouseGrabberPool()) { -#else - QPtrListIterator it(MouseGrabber::MouseGrabberPool()); - for (MouseGrabber* mg; (mg = it.current()); ++it) - { -#endif mg->checkIfGrabsMouse(e->x(), e->y(), camera()); if (mg->grabsMouse()) { @@ -1592,7 +1336,7 @@ void QGLViewer::mouseMoveEvent(QMouseEvent* e) // Check that MouseGrabber is not disabled if (mouseGrabber() == mg) { - updateGL(); + update(); break; } } @@ -1617,38 +1361,28 @@ void QGLViewer::mouseReleaseEvent(QMouseEvent* e) mouseGrabber()->checkIfGrabsMouse(e->x(), e->y(), camera()); if (!(mouseGrabber()->grabsMouse())) setMouseGrabber(NULL); - // updateGL(); + // update(); } else //#CONNECTION# mouseMoveEvent has the same structure if (camera()->frame()->isManipulated()) { - // bool updateGLNeeded = ((camera()->frame()->action_ == ZOOM_ON_REGION) || - // (camera()->frame()->action_ == SCREEN_ROTATE)); camera()->frame()->mouseReleaseEvent(e, camera()); - // if (updateGLNeeded) - // Needed in all cases because of fastDraw(). - // updateGL(); } else if ((manipulatedFrame()) && (manipulatedFrame()->isManipulated())) { - // bool updateGLNeeded = (manipulatedFrame()->action_ == SCREEN_ROTATE); if (manipulatedFrameIsACamera_) manipulatedFrame()->ManipulatedFrame::mouseReleaseEvent(e, camera()); else manipulatedFrame()->mouseReleaseEvent(e, camera()); - // if (updateGLNeeded) - // updateGL(); } -#if QT_VERSION >= 0x030000 else e->ignore(); -#endif // Not absolutely needed (see above commented code for the optimal version), but may reveal // useful for specific applications. - updateGL(); + update(); } /*! Overloading of the \c QWidget method. @@ -1661,7 +1395,7 @@ void QGLViewer::wheelEvent(QWheelEvent* e) { if (mouseGrabberIsAManipulatedFrame_) { - for (QMap::ConstIterator it=wheelBinding_.begin(), end=wheelBinding_.end(); it!=end; ++it) + for (QMap::ConstIterator it=wheelBinding_.begin(), end=wheelBinding_.end(); it!=end; ++it) if (it.value().handler == FRAME) { ManipulatedFrame* mf = dynamic_cast(mouseGrabber()); @@ -1680,45 +1414,40 @@ void QGLViewer::wheelEvent(QWheelEvent* e) } else mouseGrabber()->wheelEvent(e, camera()); - updateGL(); + update(); } else { //#CONNECTION# mousePressEvent has the same structure -#if QT_VERSION >= 0x040000 - const Qt::KeyboardModifiers modifiers = e->modifiers(); -#else - const Qt::KeyboardModifiers modifiers = e->state(); -#endif - if (wheelBinding_.contains(modifiers)) + WheelBindingPrivate wbp(e->modifiers(), currentlyPressedKey_); + + if (wheelBinding_.contains(wbp)) { - MouseActionPrivate map = wheelBinding_[modifiers]; + MouseActionPrivate map = wheelBinding_[wbp]; switch (map.handler) { - case CAMERA : - camera()->frame()->startAction(map.action, map.withConstraint); - camera()->frame()->wheelEvent(e, camera()); - break; - case FRAME : - if (manipulatedFrame()) { - if (manipulatedFrameIsACamera_) - { - manipulatedFrame()->ManipulatedFrame::startAction(map.action, map.withConstraint); - manipulatedFrame()->ManipulatedFrame::wheelEvent(e, camera()); - } - else - { - manipulatedFrame()->startAction(map.action, map.withConstraint); - manipulatedFrame()->wheelEvent(e, camera()); + case CAMERA : + camera()->frame()->startAction(map.action, map.withConstraint); + camera()->frame()->wheelEvent(e, camera()); + break; + case FRAME : + if (manipulatedFrame()) { + if (manipulatedFrameIsACamera_) + { + manipulatedFrame()->ManipulatedFrame::startAction(map.action, map.withConstraint); + manipulatedFrame()->ManipulatedFrame::wheelEvent(e, camera()); + } + else + { + manipulatedFrame()->startAction(map.action, map.withConstraint); + manipulatedFrame()->wheelEvent(e, camera()); + } } - } - break; + break; } } -#if QT_VERSION >= 0x030000 else e->ignore(); -#endif } } @@ -1729,26 +1458,14 @@ The behavior of the mouse double click depends on the mouse binding. See setMous void QGLViewer::mouseDoubleClickEvent(QMouseEvent* e) { //#CONNECTION# mousePressEvent has the same structure - ClickActionPrivate cap; - cap.doubleClick = true; -#if QT_VERSION >= 0x040000 - cap.modifiers = e->modifiers(); - cap.button = e->button(); - cap.buttonsBefore = (Qt::MouseButtons)(e->buttons() & ~(e->button())); -#else - cap.modifiers = (Qt::KeyboardModifiers)(e->state() & Qt::KeyboardModifierMask); - cap.button = (Qt::MouseButtons)((e->stateAfter() & Qt::MouseButtonMask) & (~(e->state() & Qt::MouseButtonMask))); - cap.buttonsBefore = (Qt::MouseButtons)(e->state() & Qt::MouseButtonMask); -#endif - if (clickBinding_.contains(cap)) - performClickAction(clickBinding_[cap], e); + ClickBindingPrivate cbp(e->modifiers(), e->button(), true, (Qt::MouseButtons)(e->buttons() & ~(e->button())), currentlyPressedKey_); + if (clickBinding_.contains(cbp)) + performClickAction(clickBinding_[cbp], e); else if (mouseGrabber()) mouseGrabber()->mouseDoubleClickEvent(e, camera()); -#if QT_VERSION >= 0x030000 else e->ignore(); -#endif } /*! Sets the state of displaysInStereo(). See also toggleStereoDisplay(). @@ -1770,8 +1487,7 @@ void QGLViewer::setStereoDisplay(bool stereo) Q_EMIT stereoChanged(stereo_); - if (updateGLOK_) - updateGL(); + update(); } else if (stereo) @@ -1786,11 +1502,9 @@ If the QGLViewer is embedded in an other QWidget (see QWidget::topLevelWidget()) displayed in full screen instead. */ void QGLViewer::setFullScreen(bool fullScreen) { - fullScreen_ = fullScreen; + if (fullScreen_ == fullScreen) return; - // Tricky. A timer does it later if !updateGLOK_. - if (!updateGLOK_) - return; + fullScreen_ = fullScreen; QWidget* tlw = topLevelWidget(); @@ -1822,7 +1536,7 @@ void QGLViewer::setMouseGrabber(MouseGrabber* mouseGrabber) mouseGrabberIsAManipulatedFrame_ = (dynamic_cast(mouseGrabber) != NULL); mouseGrabberIsAManipulatedCameraFrame_ = ((dynamic_cast(mouseGrabber) != NULL) && - (mouseGrabber != camera()->frame())); + (mouseGrabber != camera()->frame())); Q_EMIT mouseGrabberChanged(mouseGrabber); } @@ -1835,67 +1549,22 @@ void QGLViewer::setMouseGrabberIsEnabled(const qglviewer::MouseGrabber* const mo disabledMouseGrabbers_[reinterpret_cast(mouseGrabber)]; } -static QString keyboardModifiersString(Qt::KeyboardModifiers m, bool noButton=false) -{ -#if QT_VERSION >= 0x040000 - if (noButton && (m==Qt::NoModifier)) -#else - if (noButton && (m==Qt::NoButton)) -#endif - return QGLViewer::tr("(no button)"); - - QString keySequence = ""; - -#if QT_VERSION >= 0x040000 - if (m & Qt::ControlModifier) keySequence += "Ctrl+"; - if (m & Qt::AltModifier) keySequence += "Alt+"; - if (m & Qt::ShiftModifier) keySequence += "Shift+"; - if (m & Qt::MetaModifier) keySequence += "Meta+"; -#else - if (m & Qt::ControlButton) keySequence += "Ctrl+"; - if (m & Qt::AltButton) keySequence += "Alt+"; - if (m & Qt::ShiftButton) keySequence += "Shift+"; -# if QT_VERSION >= 0x030000 - if (m & Qt::MetaButton) keySequence += "Meta+"; -# endif -#endif - - if (keySequence.length() > 0) -#if QT_VERSION >= 0x040000 - return QKeySequence(keySequence+"X").toString(QKeySequence::NativeText).replace("X", ""); -#else - return QString(QKeySequence(keySequence+"X")).replace("X", ""); -#endif - else - return QString(); -} - -static QString mouseButtonsString(Qt::MouseButtons b) -{ - QString result(""); - bool addAmpersand = false; - if (b & Qt::LeftButton) { result += QGLViewer::tr("Left", "left mouse button"); addAmpersand=true; } - if (b & Qt::MidButton) { if (addAmpersand) result += " & "; result += QGLViewer::tr("Middle", "middle mouse button"); addAmpersand=true; } - if (b & Qt::RightButton) { if (addAmpersand) result += " & "; result += QGLViewer::tr("Right", "right mouse button"); } - return result; -} - QString QGLViewer::mouseActionString(QGLViewer::MouseAction ma) { switch (ma) { - case QGLViewer::NO_MOUSE_ACTION : return QString::null; - case QGLViewer::ROTATE : return QGLViewer::tr("Rotates", "ROTATE mouse action"); - case QGLViewer::ZOOM : return QGLViewer::tr("Zooms", "ZOOM mouse action"); - case QGLViewer::TRANSLATE : return QGLViewer::tr("Translates", "TRANSLATE mouse action"); - case QGLViewer::MOVE_FORWARD : return QGLViewer::tr("Moves forward", "MOVE_FORWARD mouse action"); - case QGLViewer::LOOK_AROUND : return QGLViewer::tr("Looks around", "LOOK_AROUND mouse action"); - case QGLViewer::MOVE_BACKWARD : return QGLViewer::tr("Moves backward", "MOVE_BACKWARD mouse action"); - case QGLViewer::SCREEN_ROTATE : return QGLViewer::tr("Rotates in screen plane", "SCREEN_ROTATE mouse action"); - case QGLViewer::ROLL : return QGLViewer::tr("Rolls", "ROLL mouse action"); - case QGLViewer::DRIVE : return QGLViewer::tr("Drives", "DRIVE mouse action"); - case QGLViewer::SCREEN_TRANSLATE : return QGLViewer::tr("Horizontally/Vertically translates", "SCREEN_TRANSLATE mouse action"); - case QGLViewer::ZOOM_ON_REGION : return QGLViewer::tr("Zooms on region for", "ZOOM_ON_REGION mouse action"); + case QGLViewer::NO_MOUSE_ACTION : return QString::null; + case QGLViewer::ROTATE : return QGLViewer::tr("Rotates", "ROTATE mouse action"); + case QGLViewer::ZOOM : return QGLViewer::tr("Zooms", "ZOOM mouse action"); + case QGLViewer::TRANSLATE : return QGLViewer::tr("Translates", "TRANSLATE mouse action"); + case QGLViewer::MOVE_FORWARD : return QGLViewer::tr("Moves forward", "MOVE_FORWARD mouse action"); + case QGLViewer::LOOK_AROUND : return QGLViewer::tr("Looks around", "LOOK_AROUND mouse action"); + case QGLViewer::MOVE_BACKWARD : return QGLViewer::tr("Moves backward", "MOVE_BACKWARD mouse action"); + case QGLViewer::SCREEN_ROTATE : return QGLViewer::tr("Rotates in screen plane", "SCREEN_ROTATE mouse action"); + case QGLViewer::ROLL : return QGLViewer::tr("Rolls", "ROLL mouse action"); + case QGLViewer::DRIVE : return QGLViewer::tr("Drives", "DRIVE mouse action"); + case QGLViewer::SCREEN_TRANSLATE : return QGLViewer::tr("Horizontally/Vertically translates", "SCREEN_TRANSLATE mouse action"); + case QGLViewer::ZOOM_ON_REGION : return QGLViewer::tr("Zooms on region for", "ZOOM_ON_REGION mouse action"); } return QString::null; } @@ -1904,79 +1573,119 @@ QString QGLViewer::clickActionString(QGLViewer::ClickAction ca) { switch (ca) { - case QGLViewer::NO_CLICK_ACTION : return QString::null; - case QGLViewer::ZOOM_ON_PIXEL : return QGLViewer::tr("Zooms on pixel", "ZOOM_ON_PIXEL click action"); - case QGLViewer::ZOOM_TO_FIT : return QGLViewer::tr("Zooms to fit scene", "ZOOM_TO_FIT click action"); - case QGLViewer::SELECT : return QGLViewer::tr("Selects", "SELECT click action"); - case QGLViewer::RAP_FROM_PIXEL : return QGLViewer::tr("Sets revolve around point", "RAP_FROM_PIXEL click action"); - case QGLViewer::RAP_IS_CENTER : return QGLViewer::tr("Resets revolve around point", "RAP_IS_CENTER click action"); - case QGLViewer::CENTER_FRAME : return QGLViewer::tr("Centers frame", "CENTER_FRAME click action"); - case QGLViewer::CENTER_SCENE : return QGLViewer::tr("Centers scene", "CENTER_SCENE click action"); - case QGLViewer::SHOW_ENTIRE_SCENE : return QGLViewer::tr("Shows entire scene", "SHOW_ENTIRE_SCENE click action"); - case QGLViewer::ALIGN_FRAME : return QGLViewer::tr("Aligns frame", "ALIGN_FRAME click action"); - case QGLViewer::ALIGN_CAMERA : return QGLViewer::tr("Aligns camera", "ALIGN_CAMERA click action"); + case QGLViewer::NO_CLICK_ACTION : return QString::null; + case QGLViewer::ZOOM_ON_PIXEL : return QGLViewer::tr("Zooms on pixel", "ZOOM_ON_PIXEL click action"); + case QGLViewer::ZOOM_TO_FIT : return QGLViewer::tr("Zooms to fit scene", "ZOOM_TO_FIT click action"); + case QGLViewer::SELECT : return QGLViewer::tr("Selects", "SELECT click action"); + case QGLViewer::RAP_FROM_PIXEL : return QGLViewer::tr("Sets pivot point", "RAP_FROM_PIXEL click action"); + case QGLViewer::RAP_IS_CENTER : return QGLViewer::tr("Resets pivot point", "RAP_IS_CENTER click action"); + case QGLViewer::CENTER_FRAME : return QGLViewer::tr("Centers manipulated frame", "CENTER_FRAME click action"); + case QGLViewer::CENTER_SCENE : return QGLViewer::tr("Centers scene", "CENTER_SCENE click action"); + case QGLViewer::SHOW_ENTIRE_SCENE : return QGLViewer::tr("Shows entire scene", "SHOW_ENTIRE_SCENE click action"); + case QGLViewer::ALIGN_FRAME : return QGLViewer::tr("Aligns manipulated frame", "ALIGN_FRAME click action"); + case QGLViewer::ALIGN_CAMERA : return QGLViewer::tr("Aligns camera", "ALIGN_CAMERA click action"); } return QString::null; } -QString QGLViewer::formatClickActionPrivate(ClickActionPrivate cap) +static QString keyString(unsigned int key) { - bool buttonsBefore = cap.buttonsBefore != Qt::NoButton; +# if QT_VERSION >= 0x040100 + return QKeySequence(int(key)).toString(QKeySequence::NativeText); +# else + return QString(QKeySequence(key)); +# endif +} + +QString QGLViewer::formatClickActionPrivate(ClickBindingPrivate cbp) +{ + bool buttonsBefore = cbp.buttonsBefore != Qt::NoButton; + QString keyModifierString = keyString(cbp.modifiers + cbp.key); + if (!keyModifierString.isEmpty()) { +#ifdef Q_OS_MAC + // modifiers never has a '+' sign. Add one space to clearly separate modifiers (and possible key) from button + keyModifierString += " "; +#else + // modifiers might be of the form : 'S' or 'Ctrl+S' or 'Ctrl+'. For consistency, add an other '+' if needed, no spaces + if (!keyModifierString.endsWith('+')) + keyModifierString += "+"; +#endif + } + return tr("%1%2%3%4%5%6", "Modifier / button or wheel / double click / with / button / pressed") - .arg(keyboardModifiersString(cap.modifiers)) - .arg(mouseButtonsString(cap.button)+(cap.button == Qt::NoButton ? tr("Wheel", "Mouse wheel") : "")) - .arg(cap.doubleClick ? tr(" double click", "Suffix after mouse button") : "") - .arg(buttonsBefore ? tr(" with ", "As in : Left button with Ctrl pressed") : "") - .arg(buttonsBefore ? mouseButtonsString(cap.buttonsBefore) : "") - .arg(buttonsBefore ? tr(" pressed", "As in : Left button with Ctrl pressed") : ""); + .arg(keyModifierString) + .arg(mouseButtonsString(cbp.button)+(cbp.button == Qt::NoButton ? tr("Wheel", "Mouse wheel") : "")) + .arg(cbp.doubleClick ? tr(" double click", "Suffix after mouse button") : "") + .arg(buttonsBefore ? tr(" with ", "As in : Left button with Ctrl pressed") : "") + .arg(buttonsBefore ? mouseButtonsString(cbp.buttonsBefore) : "") + .arg(buttonsBefore ? tr(" pressed", "As in : Left button with Ctrl pressed") : ""); } -/*! Provides a custom mouse binding description, displayed in the help() window Mouse tab. +bool QGLViewer::isValidShortcutKey(int key) { + return (key >= Qt::Key_Any && key < Qt::Key_Escape) || (key >= Qt::Key_F1 && key <= Qt::Key_F35); +} + +#ifndef DOXYGEN +/*! This method is deprecated since version 2.5.0 + + Use setMouseBindingDescription(Qt::KeyboardModifiers, Qt::MouseButtons, QString, bool, Qt::MouseButtons) instead. +*/ +void QGLViewer::setMouseBindingDescription(unsigned int state, QString description, bool doubleClick, Qt::MouseButtons buttonsBefore) { + qWarning("setMouseBindingDescription(int state,...) is deprecated. Use the modifier/button equivalent"); + setMouseBindingDescription(keyboardModifiersFromState(state), + mouseButtonFromState(state), + description, + doubleClick, + buttonsBefore); +} +#endif -\p state is a combination of Qt::KeyboardModifiers (\c Qt::ControlModifier, \c Qt::AltModifier, \c -Qt::ShiftModifier, \c Qt::MetaModifier) and Qt::MouseButtons (\c Qt::LeftButton, \c Qt::MidButton and -\c Qt::RightButton), combined using the \c "|" bitwise operator or simply "+". One can also use the -shorter \c Qt::ALT, \c Qt::CTRL, \c Qt::SHIFT or \c QT::META. +/*! Defines a custom mouse binding description, displayed in the help() window's Mouse tab. + + Same as calling setMouseBindingDescription(Qt::Key, Qt::KeyboardModifiers, Qt::MouseButton, QString, bool, Qt::MouseButtons), + with a key value of Qt::Key(0) (i.e. binding description when no regular key needs to be pressed). */ +void QGLViewer::setMouseBindingDescription(Qt::KeyboardModifiers modifiers, Qt::MouseButton button, QString description, bool doubleClick, Qt::MouseButtons buttonsBefore) +{ + setMouseBindingDescription(Qt::Key(0), modifiers, button, description, doubleClick, buttonsBefore); +} + +/*! Defines a custom mouse binding description, displayed in the help() window's Mouse tab. + +\p modifiers is a combination of Qt::KeyboardModifiers (\c Qt::ControlModifier, \c Qt::AltModifier, \c +Qt::ShiftModifier, \c Qt::MetaModifier). Possibly combined using the \c "|" operator. + +\p button is one of the Qt::MouseButtons (\c Qt::LeftButton, \c Qt::MidButton, +\c Qt::RightButton...). \p doubleClick indicates whether or not the user has to double click this button to perform the -described action. +described action. \p buttonsBefore lists the buttons that need to be pressed before the double click. Set an empty \p description to \e remove a mouse binding description. \code -// Left and Right button together simulate a middle button -setMouseBindingDescription(Qt::LeftButton + Qt::RightButton, "Emulates a middle button"); +// The R key combined with the Left mouse button rotates the camera in the screen plane. +setMouseBindingDescription(Qt::Key_R, Qt::NoModifier, Qt::LeftButton, "Rotates camera in screen plane"); // A left button double click toggles full screen -setMouseBindingDescription(Qt::LeftButton, "Toggles full screen mode", true); +setMouseBindingDescription(Qt::NoModifier, Qt::LeftButton, "Toggles full screen mode", true); // Removes the description of Ctrl+Right button -setMouseBindingDescription(Qt::ControlModifier + Qt::RightButton, ""); +setMouseBindingDescription(Qt::ControlModifier, Qt::RightButton, ""); \endcode Overload mouseMoveEvent() and friends to implement your custom mouse behavior (see the mouseMoveEvent() documentation for an example). See the keyboardAndMouse example for an illustration. -Use setMouseBinding() and setWheelBinding() to change the standard mouse action bindings. - -\note If you use Qt version 2 or 3, the \c Modifier postfix should be replaced by \c Button in the -examples above (\c Qt::ControlButton, \c Qt::AltButton, ...). - -\note If you use Qt version 2 or 3, the \p buttonsBefore parameter type is actually a -Qt::ButtonState. */ -void QGLViewer::setMouseBindingDescription(int state, QString description, bool doubleClick, Qt::MouseButtons buttonsBefore) +Use setMouseBinding() and setWheelBinding() to change the standard mouse action bindings. */ +void QGLViewer::setMouseBindingDescription(Qt::Key key, Qt::KeyboardModifiers modifiers, Qt::MouseButton button, QString description, bool doubleClick, Qt::MouseButtons buttonsBefore) { - ClickActionPrivate cap; - cap.modifiers = Qt::KeyboardModifiers(convertToKeyboardModifiers(state) & Qt::KeyboardModifierMask); - cap.button = Qt::MouseButtons(state & Qt::MouseButtonMask); - cap.doubleClick = doubleClick; - cap.buttonsBefore = buttonsBefore; + ClickBindingPrivate cbp(modifiers, button, doubleClick, buttonsBefore, key); if (description.isEmpty()) - mouseDescription_.remove(cap); + mouseDescription_.remove(cbp); else - mouseDescription_[cap] = description; + mouseDescription_[cbp] = description; } static QString tableLine(const QString& left, const QString& right) @@ -2014,15 +1723,15 @@ QString QGLViewer::mouseString() const const QString tdtd(""); text += QString("%1%2\n"). - arg(tr("Button(s)", "Buttons column header in help window mouse tab")).arg(tr("Description", "Description column header in help window mouse tab")); + arg(tr("Button(s)", "Buttons column header in help window mouse tab")).arg(tr("Description", "Description column header in help window mouse tab")); - QMap mouseBinding; + QMap mouseBinding; // User-defined mouse bindings come first. - for (QMap::ConstIterator itm=mouseDescription_.begin(), endm=mouseDescription_.end(); itm!=endm; ++itm) + for (QMap::ConstIterator itm=mouseDescription_.begin(), endm=mouseDescription_.end(); itm!=endm; ++itm) mouseBinding[itm.key()] = itm.value(); - for (QMap::ConstIterator it=mouseBinding.begin(), end=mouseBinding.end(); it != end; ++it) + for (QMap::ConstIterator it=mouseBinding.begin(), end=mouseBinding.end(); it != end; ++it) { // Should not be needed (see setMouseBindingDescription()) if (it.value().isNull()) @@ -2031,7 +1740,7 @@ QString QGLViewer::mouseString() const text += tableLine(formatClickActionPrivate(it.key()), it.value()); } - // Optionnal separator line + // Optional separator line if (!mouseBinding.isEmpty()) { mouseBinding.clear(); @@ -2041,58 +1750,50 @@ QString QGLViewer::mouseString() const // Then concatenates the descriptions of wheelBinding_, mouseBinding_ and clickBinding_. // The order is significant and corresponds to the priorities set in mousePressEvent() (reverse priority order, last one overwrites previous) // #CONNECTION# mousePressEvent() order - for (QMap::ConstIterator itw=wheelBinding_.begin(), endw=wheelBinding_.end(); itw != endw; ++itw) + for (QMap::ConstIterator itmb=mouseBinding_.begin(), endmb=mouseBinding_.end(); + itmb != endmb; ++itmb) { - ClickActionPrivate cap; - cap.doubleClick = false; - cap.modifiers = itw.key(); - cap.button = Qt::NoButton; - cap.buttonsBefore = Qt::NoButton; + ClickBindingPrivate cbp(itmb.key().modifiers, itmb.key().button, false, Qt::NoButton, itmb.key().key); - QString text = mouseActionString(itw.value().action); + QString text = mouseActionString(itmb.value().action); if (!text.isNull()) { - switch (itw.value().handler) + switch (itmb.value().handler) { - case CAMERA: text += " " + tr("camera", "Suffix after action"); break; - case FRAME: text += " " + tr("manipulated frame", "Suffix after action"); break; + case CAMERA: text += " " + tr("camera", "Suffix after action"); break; + case FRAME: text += " " + tr("manipulated frame", "Suffix after action"); break; } - if (!(itw.value().withConstraint)) + if (!(itmb.value().withConstraint)) text += "*"; } - - mouseBinding[cap] = text; + mouseBinding[cbp] = text; } - for (QMap::ConstIterator itmb=mouseBinding_.begin(), endmb=mouseBinding_.end(); - itmb != endmb; ++itmb) + for (QMap::ConstIterator itw=wheelBinding_.begin(), endw=wheelBinding_.end(); itw != endw; ++itw) { - ClickActionPrivate cap; - cap.doubleClick = false; - cap.modifiers = Qt::KeyboardModifiers(itmb.key() & Qt::KeyboardModifierMask); - cap.button = Qt::MouseButtons(itmb.key() & Qt::MouseButtonMask); - cap.buttonsBefore = Qt::NoButton; + ClickBindingPrivate cbp(itw.key().modifiers, Qt::NoButton, false, Qt::NoButton, itw.key().key); - QString text = mouseActionString(itmb.value().action); + QString text = mouseActionString(itw.value().action); if (!text.isNull()) { - switch (itmb.value().handler) + switch (itw.value().handler) { - case CAMERA: text += " " + tr("camera", "Suffix after action"); break; - case FRAME: text += " " + tr("manipulated frame", "Suffix after action"); break; + case CAMERA: text += " " + tr("camera", "Suffix after action"); break; + case FRAME: text += " " + tr("manipulated frame", "Suffix after action"); break; } - if (!(itmb.value().withConstraint)) + if (!(itw.value().withConstraint)) text += "*"; } - mouseBinding[cap] = text; + + mouseBinding[cbp] = text; } - for (QMap::ConstIterator itcb=clickBinding_.begin(), endcb=clickBinding_.end(); itcb!=endcb; ++itcb) + for (QMap::ConstIterator itcb=clickBinding_.begin(), endcb=clickBinding_.end(); itcb!=endcb; ++itcb) mouseBinding[itcb.key()] = clickActionString(itcb.value()); - for (QMap::ConstIterator it2=mouseBinding.begin(), end2=mouseBinding.end(); it2 != end2; ++it2) + for (QMap::ConstIterator it2=mouseBinding.begin(), end2=mouseBinding.end(); it2 != end2; ++it2) { if (it2.value().isNull()) continue; @@ -2119,100 +1820,66 @@ setKeyDescription(Qt::CTRL+Qt::Key_C, ""); See the keyboardAndMouse example for illustration and the keyboard page for details. */ -void QGLViewer::setKeyDescription(int key, QString description) +void QGLViewer::setKeyDescription(unsigned int key, QString description) { -#if QT_VERSION >= 0x030000 - // #CONNECTION# keyString. In Qt 2.3, longs modifier overlap with key codes. - key = convertToKeyboardModifiers(key); -#endif if (description.isEmpty()) keyDescription_.remove(key); else keyDescription_[key] = description; } -static QString keyString(int key) -{ -#if QT_VERSION >= 0x030000 -# if QT_VERSION >= 0x040100 - return QKeySequence(convertToShortModifier(key)).toString(); -# else - return QString(QKeySequence(convertToShortModifier(key))); -# endif -#else - // #CONNECTION# setKeyDescription. In Qt 2.3, long modifiers overlap with key codes. - return QString(QKeySequence(key)); -#endif -} - QString QGLViewer::cameraPathKeysString() const { if (pathIndex_.isEmpty()) return QString::null; -#if QT_VERSION >= 0x040000 || QT_VERSION < 0x030000 - QVector keys; -#else - QValueVector keys; -#endif + QVector keys; keys.reserve(pathIndex_.count()); - for (QMap::ConstIterator i = pathIndex_.begin(), endi=pathIndex_.end(); i != endi; ++i) + for (QMap::ConstIterator i = pathIndex_.begin(), endi=pathIndex_.end(); i != endi; ++i) keys.push_back(i.key()); -#if QT_VERSION >= 0x040000 qSort(keys); -#else -# if QT_VERSION >= 0x030000 - qHeapSort(keys); -# else - sort(keys.begin(), keys.end()); -# endif -#endif -#if QT_VERSION >= 0x040000 || QT_VERSION < 0x030000 - QVector::const_iterator it = keys.begin(), end = keys.end(); -#else - QValueVector::const_iterator it = keys.begin(), end = keys.end(); -#endif + QVector::const_iterator it = keys.begin(), end = keys.end(); QString res = keyString(*it); const int maxDisplayedKeys = 6; int nbDisplayedKeys = 0; - int previousKey = (*it); + Qt::Key previousKey = (*it); int state = 0; ++it; while ((it != end) && (nbDisplayedKeys < maxDisplayedKeys-1)) { switch (state) { - case 0 : - if ((*it) == previousKey + 1) - state++; - else - { - res += ", " + keyString(*it); - nbDisplayedKeys++; - } - break; - case 1 : - if ((*it) == previousKey + 1) - state++; - else - { - res += ", " + keyString(previousKey); - res += ", " + keyString(*it); - nbDisplayedKeys += 2; - state = 0; - } - break; - default : - if ((*it) != previousKey + 1) - { - res += ".." + keyString(previousKey); - res += ", " + keyString(*it); - nbDisplayedKeys += 2; - state = 0; - } - break; + case 0 : + if ((*it) == previousKey + 1) + state++; + else + { + res += ", " + keyString(*it); + nbDisplayedKeys++; + } + break; + case 1 : + if ((*it) == previousKey + 1) + state++; + else + { + res += ", " + keyString(previousKey); + res += ", " + keyString(*it); + nbDisplayedKeys += 2; + state = 0; + } + break; + default : + if ((*it) != previousKey + 1) + { + res += ".." + keyString(previousKey); + res += ", " + keyString(*it); + nbDisplayedKeys += 2; + state = 0; + } + break; } previousKey = *it; ++it; @@ -2240,16 +1907,16 @@ QString QGLViewer::keyboardString() const { QString text("
\n"); text += QString("\n"). - arg(QGLViewer::tr("Key(s)", "Keys column header in help window mouse tab")).arg(QGLViewer::tr("Description", "Description column header in help window mouse tab")); + arg(QGLViewer::tr("Key(s)", "Keys column header in help window mouse tab")).arg(QGLViewer::tr("Description", "Description column header in help window mouse tab")); - QMap keyDescription; + QMap keyDescription; // 1 - User defined key descriptions - for (QMap::ConstIterator kd=keyDescription_.begin(), kdend=keyDescription_.end(); kd!=kdend; ++kd) + for (QMap::ConstIterator kd=keyDescription_.begin(), kdend=keyDescription_.end(); kd!=kdend; ++kd) keyDescription[kd.key()] = kd.value(); // Add to text in sorted order - for (QMap::ConstIterator kb=keyDescription.begin(), endb=keyDescription.end(); kb!=endb; ++kb) + for (QMap::ConstIterator kb=keyDescription.begin(), endb=keyDescription.end(); kb!=endb; ++kb) text += tableLine(keyString(kb.key()), kb.value()); @@ -2262,12 +1929,12 @@ QString QGLViewer::keyboardString() const // 3 - KeyboardAction bindings description - for (QMap::ConstIterator it=keyboardBinding_.begin(), end=keyboardBinding_.end(); it != end; ++it) - if ((it.value() != 0) && ((!cameraIsInRevolveMode()) || ((it.key() != INCREASE_FLYSPEED) && (it.key() != DECREASE_FLYSPEED)))) + for (QMap::ConstIterator it=keyboardBinding_.begin(), end=keyboardBinding_.end(); it != end; ++it) + if ((it.value() != 0) && ((!cameraIsInRotateMode()) || ((it.key() != INCREASE_FLYSPEED) && (it.key() != DECREASE_FLYSPEED)))) keyDescription[it.value()] = keyboardActionDescription_[it.key()]; // Add to text in sorted order - for (QMap::ConstIterator kb2=keyDescription.begin(), endb2=keyDescription.end(); kb2!=endb2; ++kb2) + for (QMap::ConstIterator kb2=keyDescription.begin(), endb2=keyDescription.end(); kb2!=endb2; ++kb2) text += tableLine(keyString(kb2.key()), kb2.value()); @@ -2276,13 +1943,13 @@ QString QGLViewer::keyboardString() const if (!cpks.isNull()) { text += "\n"; - text += tableLine(keyboardModifiersString(playPathKeyboardModifiers()) + "" + QGLViewer::tr("Fx", "Generic function key (F1..F12)") + "", - QGLViewer::tr("Plays path (or resets saved position)")); - text += tableLine(keyboardModifiersString(addKeyFrameKeyboardModifiers()) + "" + QGLViewer::tr("Fx", "Generic function key (F1..F12)") + "", - QGLViewer::tr("Adds a key frame to path (or defines a position)")); - text += tableLine(keyboardModifiersString(addKeyFrameKeyboardModifiers()) + "" + QGLViewer::tr("Fx", "Generic function key (F1..F12)") + "+" + QGLViewer::tr("Fx", "Generic function key (F1..F12)") + "", - QGLViewer::tr("Deletes path (or saved position)")); + text += QGLViewer::tr("Camera paths are controlled using the %1 keys (noted Fx below):", "Help window key tab camera keys").arg(cpks) + "\n"; + text += tableLine(keyString(playPathKeyboardModifiers()) + "" + QGLViewer::tr("Fx", "Generic function key (F1..F12)") + "", + QGLViewer::tr("Plays path (or resets saved position)")); + text += tableLine(keyString(addKeyFrameKeyboardModifiers()) + "" + QGLViewer::tr("Fx", "Generic function key (F1..F12)") + "", + QGLViewer::tr("Adds a key frame to path (or defines a position)")); + text += tableLine(keyString(addKeyFrameKeyboardModifiers()) + "" + QGLViewer::tr("Fx", "Generic function key (F1..F12)") + "+" + QGLViewer::tr("Fx", "Generic function key (F1..F12)") + "", + QGLViewer::tr("Deletes path (or saved position)")); } text += "
%1%2
\n"; - text += QGLViewer::tr("Camera paths are controlled using %1 (noted Fx below):", "Help window key tab camera keys").arg(cpks) + "
"; @@ -2292,14 +1959,10 @@ QString QGLViewer::keyboardString() const /*! Displays the help window "About" tab. See help() for details. */ void QGLViewer::aboutQGLViewer() { help(); -#if QT_VERSION >= 0x040000 - helpWidget()->setCurrentIndex(3); -#else - helpWidget()->setCurrentPage(3); -#endif + helpWidget()->setCurrentIndex(3); } - + /*! Opens a modal help window that includes four tabs, respectively filled with helpString(), keyboardString(), mouseString() and about libQGLViewer. @@ -2323,21 +1986,14 @@ void QGLViewer::help() { // Qt4 requires a NULL parent... helpWidget_ = new QTabWidget(NULL); -#if QT_VERSION >= 0x040000 helpWidget()->setWindowTitle(tr("Help", "Help window title")); -#else - helpWidget()->setCaption(tr("Help", "Help window title")); -#endif resize = true; for (int i=0; i<4; ++i) { QTextEdit* tab = new QTextEdit(NULL); -#if QT_VERSION >= 0x030000 tab->setReadOnly(true); -#endif -#if QT_VERSION >= 0x040000 helpWidget()->insertTab(i, tab, label[i]); if (i==3) { # include "qglviewer-icon.xpm" @@ -2345,63 +2001,36 @@ void QGLViewer::help() tab->document()->addResource(QTextDocument::ImageResource, QUrl("mydata://qglviewer-icon.xpm"), QVariant(pixmap)); } -#else - tab->setTextFormat(Qt::RichText); - helpWidget()->insertTab(tab, label[i]); -#endif } } - - -#if QT_VERSION < 0x030000 - const int currentPageIndex = helpWidget()->currentPageIndex(); -#endif for (int i=0; i<4; ++i) { QString text; switch (i) { - case 0 : text = helpString(); break; - case 1 : text = keyboardString(); break; - case 2 : text = mouseString(); break; - case 3 : text = QString("

") + tr( - "

libQGLViewer

" - "

Version %1


" - "A versatile 3D viewer based on OpenGL and Qt
" - "Copyright 2002-%2 Gilles Debunne
" - "%3").arg(QGLViewerVersionString()).arg("2012").arg("http://www.libqglviewer.com") + - QString("
"); + case 0 : text = helpString(); break; + case 1 : text = keyboardString(); break; + case 2 : text = mouseString(); break; + case 3 : text = QString("

") + tr( + "

libQGLViewer

" + "

Version %1


" + "A versatile 3D viewer based on OpenGL and Qt
" + "Copyright 2002-%2 Gilles Debunne
" + "%3").arg(QGLViewerVersionString()).arg("2014").arg("http://www.libqglviewer.com") + + QString("
"); break; - default : break; + default : break; } -#if QT_VERSION >= 0x040000 QTextEdit* textEdit = (QTextEdit*)(helpWidget()->widget(i)); textEdit->setHtml(text); -#else -# if QT_VERSION < 0x030000 - helpWidget()->setCurrentPage(i); - QTextEdit* textEdit = (QTextEdit*)(helpWidget()->currentPage()); -# else - QTextEdit* textEdit = (QTextEdit*)(helpWidget()->page(i)); -# endif textEdit->setText(text); -#endif -#if QT_VERSION < 0x040000 - if (resize && (textEdit->heightForWidth(width) > height)) - height = textEdit->heightForWidth(width); -#else if (resize && (textEdit->height() > height)) height = textEdit->height(); -#endif } -#if QT_VERSION < 0x030000 - helpWidget()->setCurrentPage(currentPageIndex); -#endif - if (resize) helpWidget()->resize(width, height+40); // 40 pixels is ~ tabs' height helpWidget()->show(); @@ -2419,11 +2048,11 @@ void Viewer::keyPressEvent(QKeyEvent *e) // Defines the Alt+R shortcut. if ((e->key() == Qt::Key_R) && (e->modifiers() == Qt::AltModifier)) { - myResetFunction(); - updateGL(); // Refresh display + myResetFunction(); + update(); // Refresh display } else - QGLViewer::keyPressEvent(e); + QGLViewer::keyPressEvent(e); } // With Qt 2 or 3, you would retrieve modifiers keys using : @@ -2443,15 +2072,12 @@ void QGLViewer::keyPressEvent(QKeyEvent *e) } const Qt::Key key = Qt::Key(e->key()); -#if QT_VERSION >= 0x040000 - const Qt::KeyboardModifiers modifiers = e->modifiers(); -#else - const Qt::KeyboardModifiers modifiers = (Qt::KeyboardModifiers)(e->state() & Qt::KeyboardModifierMask); -#endif - QMap::ConstIterator it=keyboardBinding_.begin(), end=keyboardBinding_.end(); - const unsigned int target = key | modifiers; - while ((it != end) && (it.value() != target)) + const Qt::KeyboardModifiers modifiers = e->modifiers(); + + QMap::ConstIterator it=keyboardBinding_.begin(), end=keyboardBinding_.end(); + const unsigned int target = key | modifiers; + while ((it != end) && (it.value() != target)) ++it; if (it != end) @@ -2460,9 +2086,10 @@ void QGLViewer::keyPressEvent(QKeyEvent *e) if (pathIndex_.contains(Qt::Key(key))) { // Camera paths - int index = pathIndex_[Qt::Key(key)]; + unsigned int index = pathIndex_[Qt::Key(key)]; - static QTime doublePress; // try to double press on two viewers at the same time ! + // not safe, but try to double press on two viewers at the same time ! + static QTime doublePress; if (modifiers == playPathKeyboardModifiers()) { @@ -2489,7 +2116,7 @@ void QGLViewer::keyPressEvent(QKeyEvent *e) { if (camera()->keyFrameInterpolator(index)) { - disconnect(camera()->keyFrameInterpolator(index), SIGNAL(interpolated()), this, SLOT(updateGL())); + disconnect(camera()->keyFrameInterpolator(index), SIGNAL(interpolated()), this, SLOT(update())); if (camera()->keyFrameInterpolator(index)->numberOfKeyFrames() > 1) displayMessage(tr("Path %1 deleted", "Feedback message").arg(index)); else @@ -2502,7 +2129,7 @@ void QGLViewer::keyPressEvent(QKeyEvent *e) bool nullBefore = (camera()->keyFrameInterpolator(index) == NULL); camera()->addKeyFrameToPath(index); if (nullBefore) - connect(camera()->keyFrameInterpolator(index), SIGNAL(interpolated()), SLOT(updateGL())); + connect(camera()->keyFrameInterpolator(index), SIGNAL(interpolated()), SLOT(update())); int nbKF = camera()->keyFrameInterpolator(index)->numberOfKeyFrames(); if (nbKF > 1) displayMessage(tr("Path %1, position %2 added", "Feedback message").arg(index).arg(nbKF)); @@ -2511,52 +2138,57 @@ void QGLViewer::keyPressEvent(QKeyEvent *e) } previousPathId_ = index; } - updateGL(); - } - else + update(); + } else { + if (isValidShortcutKey(key)) currentlyPressedKey_ = key; e->ignore(); + } +} + +void QGLViewer::keyReleaseEvent(QKeyEvent * e) { + if (isValidShortcutKey(e->key())) currentlyPressedKey_ = Qt::Key(0); } void QGLViewer::handleKeyboardAction(KeyboardAction id) { switch (id) { - case DRAW_AXIS : toggleAxisIsDrawn(); break; - case DRAW_GRID : toggleGridIsDrawn(); break; - case DISPLAY_FPS : toggleFPSIsDisplayed(); break; - case ENABLE_TEXT : toggleTextIsEnabled(); break; - case EXIT_VIEWER : saveStateToFileForAllViewers(); qApp->closeAllWindows(); break; - case SAVE_SCREENSHOT : saveSnapshot(false, false); break; - case FULL_SCREEN : toggleFullScreen(); break; - case STEREO : toggleStereoDisplay(); break; - case ANIMATION : toggleAnimation(); break; - case HELP : help(); break; - case EDIT_CAMERA : toggleCameraIsEdited(); break; - case SNAPSHOT_TO_CLIPBOARD : snapshotToClipboard(); break; - case CAMERA_MODE : - toggleCameraMode(); - displayMessage(cameraIsInRevolveMode()?tr("Camera in revolve around mode", "Feedback message"):tr("Camera in fly mode", "Feedback message")); - break; - - case MOVE_CAMERA_LEFT : - camera()->frame()->translate(camera()->frame()->inverseTransformOf(Vec(-10.0*camera()->flySpeed(), 0.0, 0.0))); - updateGL(); - break; - case MOVE_CAMERA_RIGHT : - camera()->frame()->translate(camera()->frame()->inverseTransformOf(Vec( 10.0*camera()->flySpeed(), 0.0, 0.0))); - updateGL(); - break; - case MOVE_CAMERA_UP : - camera()->frame()->translate(camera()->frame()->inverseTransformOf(Vec(0.0, 10.0*camera()->flySpeed(), 0.0))); - updateGL(); - break; - case MOVE_CAMERA_DOWN : - camera()->frame()->translate(camera()->frame()->inverseTransformOf(Vec(0.0, -10.0*camera()->flySpeed(), 0.0))); - updateGL(); - break; - - case INCREASE_FLYSPEED : camera()->setFlySpeed(camera()->flySpeed() * 1.5); break; - case DECREASE_FLYSPEED : camera()->setFlySpeed(camera()->flySpeed() / 1.5); break; + case DRAW_AXIS : toggleAxisIsDrawn(); break; + case DRAW_GRID : toggleGridIsDrawn(); break; + case DISPLAY_FPS : toggleFPSIsDisplayed(); break; + case ENABLE_TEXT : toggleTextIsEnabled(); break; + case EXIT_VIEWER : saveStateToFileForAllViewers(); qApp->closeAllWindows(); break; + case SAVE_SCREENSHOT : saveSnapshot(false, false); break; + case FULL_SCREEN : toggleFullScreen(); break; + case STEREO : toggleStereoDisplay(); break; + case ANIMATION : toggleAnimation(); break; + case HELP : help(); break; + case EDIT_CAMERA : toggleCameraIsEdited(); break; + case SNAPSHOT_TO_CLIPBOARD : snapshotToClipboard(); break; + case CAMERA_MODE : + toggleCameraMode(); + displayMessage(cameraIsInRotateMode()?tr("Camera in observer mode", "Feedback message"):tr("Camera in fly mode", "Feedback message")); + break; + + case MOVE_CAMERA_LEFT : + camera()->frame()->translate(camera()->frame()->inverseTransformOf(Vec(-10.0*camera()->flySpeed(), 0.0, 0.0))); + update(); + break; + case MOVE_CAMERA_RIGHT : + camera()->frame()->translate(camera()->frame()->inverseTransformOf(Vec( 10.0*camera()->flySpeed(), 0.0, 0.0))); + update(); + break; + case MOVE_CAMERA_UP : + camera()->frame()->translate(camera()->frame()->inverseTransformOf(Vec(0.0, 10.0*camera()->flySpeed(), 0.0))); + update(); + break; + case MOVE_CAMERA_DOWN : + camera()->frame()->translate(camera()->frame()->inverseTransformOf(Vec(0.0, -10.0*camera()->flySpeed(), 0.0))); + update(); + break; + + case INCREASE_FLYSPEED : camera()->setFlySpeed(camera()->flySpeed() * 1.5); break; + case DECREASE_FLYSPEED : camera()->setFlySpeed(camera()->flySpeed() / 1.5); break; } } @@ -2594,7 +2226,7 @@ previous ones). If several KeyboardAction are binded to the same shortcut, only active. */ void QGLViewer::setShortcut(KeyboardAction action, unsigned int key) { - keyboardBinding_[action] = convertToKeyboardModifiers(key); + keyboardBinding_[action] = key; } /*! Returns the keyboard shortcut associated to a given QGLViewer::KeyboardAction. @@ -2615,19 +2247,19 @@ illustration. */ unsigned int QGLViewer::shortcut(KeyboardAction action) const { if (keyboardBinding_.contains(action)) - return convertToShortModifier(keyboardBinding_[action]); + return keyboardBinding_[action]; else return 0; } #ifndef DOXYGEN -void QGLViewer::setKeyboardAccelerator(KeyboardAction action, int key) +void QGLViewer::setKeyboardAccelerator(KeyboardAction action, unsigned int key) { qWarning("setKeyboardAccelerator is deprecated. Use setShortcut instead."); setShortcut(action, key); } -int QGLViewer::keyboardAccelerator(KeyboardAction action) const +unsigned int QGLViewer::keyboardAccelerator(KeyboardAction action) const { qWarning("keyboardAccelerator is deprecated. Use shortcut instead."); return shortcut(action); @@ -2651,9 +2283,9 @@ If several keys are binded to a given \p index (see setPathKey()), one of them i Returns \c 0 if no key is associated with this index. See also the keyboard page. */ -Qt::Key QGLViewer::pathKey(int index) const +Qt::Key QGLViewer::pathKey(unsigned int index) const { - for (QMap::ConstIterator it = pathIndex_.begin(), end=pathIndex_.end(); it != end; ++it) + for (QMap::ConstIterator it = pathIndex_.begin(), end=pathIndex_.end(); it != end; ++it) if (it.value() == index) return it.key(); return Qt::Key(0); @@ -2670,24 +2302,25 @@ setPathKey(Qt::Key_Space, 0); // Remove this binding setPathKey(-Qt::Key_Space); \endcode */ -void QGLViewer::setPathKey(int key, int index) +void QGLViewer::setPathKey(int key, unsigned int index) { + Qt::Key k = Qt::Key(abs(key)); if (key < 0) - pathIndex_.remove(Qt::Key(-key)); + pathIndex_.remove(k); else - pathIndex_[Qt::Key(key)] = index; + pathIndex_[k] = index; } /*! Sets the playPathKeyboardModifiers() value. */ void QGLViewer::setPlayPathKeyboardModifiers(Qt::KeyboardModifiers modifiers) { - playPathKeyboardModifiers_ = convertKeyboardModifiers(modifiers); + playPathKeyboardModifiers_ = modifiers; } /*! Sets the addKeyFrameKeyboardModifiers() value. */ void QGLViewer::setAddKeyFrameKeyboardModifiers(Qt::KeyboardModifiers modifiers) { - addKeyFrameKeyboardModifiers_ = convertKeyboardModifiers(modifiers); + addKeyFrameKeyboardModifiers_ = modifiers; } /*! Returns the keyboard modifiers that must be pressed with a pathKey() to add the current camera @@ -2698,11 +2331,7 @@ Qt::MetaModifier or a combination of these (using the bitwise '|' operator). Default value is Qt::AltModifier. Defined using setAddKeyFrameKeyboardModifiers(). -See also playPathKeyboardModifiers(). - -\note If you use Qt version 2 or 3, the \c Qt::KeyboardModifiers is actually a \c Qt::ButtonState. -The \c Modifier postfix is replaced by \c Button in the enums' names (\c Qt::ControlButton, \c -Qt::AltButton, ...). */ +See also playPathKeyboardModifiers(). */ Qt::KeyboardModifiers QGLViewer::addKeyFrameKeyboardModifiers() const { return addKeyFrameKeyboardModifiers_; @@ -2715,11 +2344,7 @@ Qt::MetaModifier or a combination of these (using the bitwise '|' operator). Default value is Qt::NoModifier. Defined using setPlayPathKeyboardModifiers(). -See also addKeyFrameKeyboardModifiers(). - -\note If you use Qt version 2 or 3, the \c Qt::KeyboardModifiers is actually a \c Qt::ButtonState. -The \c Modifier postfix is replaced by \c Button in the enums' names (\c Qt::ControlButton, \c -Qt::AltButton, ...). */ +See also addKeyFrameKeyboardModifiers(). */ Qt::KeyboardModifiers QGLViewer::playPathKeyboardModifiers() const { return playPathKeyboardModifiers_; @@ -2738,19 +2363,19 @@ Qt::KeyboardModifiers QGLViewer::playPathStateKey() const return playPathKeyboardModifiers(); } -void QGLViewer::setAddKeyFrameStateKey(int buttonState) +void QGLViewer::setAddKeyFrameStateKey(unsigned int buttonState) { qWarning("setAddKeyFrameStateKey has been renamed setAddKeyFrameKeyboardModifiers"); - setAddKeyFrameKeyboardModifiers(Qt::KeyboardModifiers(buttonState & Qt::KeyboardModifierMask)); + setAddKeyFrameKeyboardModifiers(keyboardModifiersFromState(buttonState)); } -void QGLViewer::setPlayPathStateKey(int buttonState) +void QGLViewer::setPlayPathStateKey(unsigned int buttonState) { qWarning("setPlayPathStateKey has been renamed setPlayPathKeyboardModifiers"); - setPlayPathKeyboardModifiers(Qt::KeyboardModifiers(buttonState & Qt::KeyboardModifierMask)); + setPlayPathKeyboardModifiers(keyboardModifiersFromState(buttonState)); } -Qt::Key QGLViewer::keyFrameKey(int index) const +Qt::Key QGLViewer::keyFrameKey(unsigned int index) const { qWarning("keyFrameKey has been renamed pathKey."); return pathKey(index); @@ -2762,27 +2387,29 @@ Qt::KeyboardModifiers QGLViewer::playKeyFramePathStateKey() const return playPathKeyboardModifiers(); } -void QGLViewer::setKeyFrameKey(int index, int key) +void QGLViewer::setKeyFrameKey(unsigned int index, int key) { qWarning("setKeyFrameKey is deprecated, use setPathKey instead, with swapped parameters."); setPathKey(key, index); } -void QGLViewer::setPlayKeyFramePathStateKey(int buttonState) +void QGLViewer::setPlayKeyFramePathStateKey(unsigned int buttonState) { qWarning("setPlayKeyFramePathStateKey has been renamed setPlayPathKeyboardModifiers."); - setPlayPathKeyboardModifiers(Qt::KeyboardModifiers(buttonState & Qt::KeyboardModifierMask)); + setPlayPathKeyboardModifiers(keyboardModifiersFromState(buttonState)); } #endif //////////////////////////////////////////////////////////////////////////////// // M o u s e b e h a v i o r s t a t e k e y s // //////////////////////////////////////////////////////////////////////////////// -/*! Associates keyboard modifiers to MouseHandler \p handler. +#ifndef DOXYGEN +/*! This method has been deprecated since version 2.5.0 + +Associates keyboard modifiers to MouseHandler \p handler. The \p modifiers parameter is \c Qt::AltModifier, \c Qt::ShiftModifier, \c Qt::ControlModifier, \c -Qt::MetaModifier or a combination of these using the '|' bitwise operator. Some shorter names are -also available: \c Qt::ALT, \c Qt::CTRL, \c Qt::SHIFT or \c QT::META. +Qt::MetaModifier or a combination of these using the '|' bitwise operator. \e All the \p handler's associated bindings will then need the specified \p modifiers key(s) to be activated. @@ -2790,7 +2417,7 @@ activated. With this code, \code setHandlerKeyboardModifiers(QGLViewer::CAMERA, Qt::AltModifier); -setHandlerKeyboardModifiers(QGLViewer::FRAME, Qt::NoModifier); +setHandlerKeyboardModifiers(QGLViewer::FRAME, Qt::NoModifier); \endcode you will have to press the \c Alt key while pressing mouse buttons in order to move the camera(), while no key will be needed to move the manipulatedFrame(). @@ -2814,19 +2441,17 @@ setHandlerKeyboardModifiers(QGLViewer::FRAME, Qt::AltModifier); setHandlerKeyboardModifiers(QGLViewer::CAMERA, Qt::ControlModifier); // And finally, FRAME can be associated with NoModifier setHandlerKeyboardModifiers(QGLViewer::FRAME, Qt::NoModifier); -\endcode - -\note If you use Qt version 2 or 3, \p modifiers is actually a \c Qt::ButtonState. The \c Modifier -sufix is replaced by \c Button in the enums' names (\c Qt::ControlButton, \c Qt::AltButton, -\c Qt::ShiftButton and \c Qt::MetaButton). */ +\endcode */ void QGLViewer::setHandlerKeyboardModifiers(MouseHandler handler, Qt::KeyboardModifiers modifiers) { - QMap newMouseBinding; - QMap newWheelBinding; - QMap newClickBinding_; + qWarning("setHandlerKeyboardModifiers is deprecated, call setMouseBinding() instead"); + + QMap newMouseBinding; + QMap newWheelBinding; + QMap newClickBinding_; - QMap::Iterator mit; - QMap::Iterator wit; + QMap::Iterator mit; + QMap::Iterator wit; // First copy unchanged bindings. for (mit = mouseBinding_.begin(); mit != mouseBinding_.end(); ++mit) @@ -2838,139 +2463,165 @@ void QGLViewer::setHandlerKeyboardModifiers(MouseHandler handler, Qt::KeyboardMo newWheelBinding[wit.key()] = wit.value(); // Then, add modified bindings, that can overwrite the previous ones. - modifiers = convertKeyboardModifiers(modifiers); for (mit = mouseBinding_.begin(); mit != mouseBinding_.end(); ++mit) if ((mit.value().handler == handler) && (mit.value().action != ZOOM_ON_REGION)) { - int newState = modifiers | (mit.key() & Qt::MouseButtonMask); - newMouseBinding[newState] = mit.value(); + MouseBindingPrivate mbp(modifiers, mit.key().button, mit.key().key); + newMouseBinding[mbp] = mit.value(); } - for (wit = wheelBinding_.begin(); wit != wheelBinding_.end(); ++wit) - if (wit.value().handler == handler) - { - Qt::KeyboardModifiers newState = modifiers; - newWheelBinding[newState] = wit.value(); - } + for (wit = wheelBinding_.begin(); wit != wheelBinding_.end(); ++wit) + if (wit.value().handler == handler) + { + WheelBindingPrivate wbp(modifiers, wit.key().key); + newWheelBinding[wbp] = wit.value(); + } - // Same for button bindings - for (QMap::ConstIterator cb=clickBinding_.begin(), end=clickBinding_.end(); cb != end; ++cb) - if (((handler==CAMERA) && ((cb.value() == CENTER_SCENE) || (cb.value() == ALIGN_CAMERA))) || - ((handler==FRAME) && ((cb.value() == CENTER_FRAME) || (cb.value() == ALIGN_FRAME)))) - { - ClickActionPrivate cap; - cap.modifiers = modifiers; - cap.button = cb.key().button; - cap.doubleClick = cb.key().doubleClick; - cap.buttonsBefore = cb.key().buttonsBefore; - newClickBinding_[cap] = cb.value(); - } - else - newClickBinding_[cb.key()] = cb.value(); + // Same for button bindings + for (QMap::ConstIterator cb=clickBinding_.begin(), end=clickBinding_.end(); cb != end; ++cb) + if (((handler==CAMERA) && ((cb.value() == CENTER_SCENE) || (cb.value() == ALIGN_CAMERA))) || + ((handler==FRAME) && ((cb.value() == CENTER_FRAME) || (cb.value() == ALIGN_FRAME)))) + { + ClickBindingPrivate cbp(modifiers, cb.key().button, cb.key().doubleClick, cb.key().buttonsBefore, cb.key().key); + newClickBinding_[cbp] = cb.value(); + } + else + newClickBinding_[cb.key()] = cb.value(); - mouseBinding_ = newMouseBinding; - wheelBinding_ = newWheelBinding; - clickBinding_ = newClickBinding_; + mouseBinding_ = newMouseBinding; + wheelBinding_ = newWheelBinding; + clickBinding_ = newClickBinding_; } - -#ifndef DOXYGEN -void QGLViewer::setHandlerStateKey(MouseHandler handler, int buttonState) +void QGLViewer::setHandlerStateKey(MouseHandler handler, unsigned int buttonState) { qWarning("setHandlerStateKey has been renamed setHandlerKeyboardModifiers"); - setHandlerKeyboardModifiers(handler, Qt::KeyboardModifiers(buttonState & Qt::KeyboardModifierMask)); + setHandlerKeyboardModifiers(handler, keyboardModifiersFromState(buttonState)); } -void QGLViewer::setMouseStateKey(MouseHandler handler, int buttonState) +void QGLViewer::setMouseStateKey(MouseHandler handler, unsigned int buttonState) { qWarning("setMouseStateKey has been renamed setHandlerKeyboardModifiers."); - setHandlerKeyboardModifiers(handler, Qt::KeyboardModifiers(buttonState & Qt::KeyboardModifierMask)); + setHandlerKeyboardModifiers(handler, keyboardModifiersFromState(buttonState)); +} + +/*! This method is deprecated since version 2.5.0 + + Use setMouseBinding(Qt::KeyboardModifiers, Qt::MouseButtons, MouseHandler, MouseAction, bool) instead. +*/ +void QGLViewer::setMouseBinding(unsigned int state, MouseHandler handler, MouseAction action, bool withConstraint) +{ + qWarning("setMouseBinding(int state, MouseHandler...) is deprecated. Use the modifier/button equivalent"); + setMouseBinding(keyboardModifiersFromState(state), + mouseButtonFromState(state), + handler, + action, + withConstraint); } #endif -/*! Associates a MouseAction to any mouse button and keyboard modifiers \p state combination. The -receiver of the mouse events is a MouseHandler (QGLViewer::CAMERA or QGLViewer::FRAME). +/*! Defines a MouseAction binding. -The parameters should read: when the \p state mouse button and keyboard modifiers are pressed, -activate \p action on \p handler. If \p withConstraint is \c true (default), the -qglviewer::Frame::constraint() associated with the Frame will be enforced during motion. + Same as calling setMouseBinding(Qt::Key, Qt::KeyboardModifiers, Qt::MouseButton, MouseHandler, MouseAction, bool), + with a key value of Qt::Key(0) (i.e. no regular extra key needs to be pressed to perform this action). */ +void QGLViewer::setMouseBinding(Qt::KeyboardModifiers modifiers, Qt::MouseButton button, MouseHandler handler, MouseAction action, bool withConstraint) { + setMouseBinding(Qt::Key(0), modifiers, button, handler, action, withConstraint); +} -Use the '|' bitwise operator or '+' to combine keys and buttons: +/*! Associates a MouseAction to any mouse \p button, while keyboard \p modifiers and \p key are pressed. +The receiver of the mouse events is a MouseHandler (QGLViewer::CAMERA or QGLViewer::FRAME). + +The parameters should read: when the mouse \p button is pressed, while the keyboard \p modifiers and \p key are down, +activate \p action on \p handler. Use Qt::NoModifier to indicate that no modifier +key is needed, and a \p key value of 0 if no regular key has to be pressed +(or simply use setMouseBinding(Qt::KeyboardModifiers, Qt::MouseButton, MouseHandler, MouseAction, bool)). + +Use the '|' operator to combine modifiers: \code -// Left and right buttons together make a camera zoom: emulates a mouse third button if needed. -setMouseBinding(Qt::LeftButton + Qt::RightButton, CAMERA, ZOOM); +// The R key combined with the Left mouse button rotates the camera in the screen plane. +setMouseBinding(Qt::Key_R, Qt::NoModifier, Qt::LeftButton, CAMERA, SCREEN_ROTATE); -// Alt + Shift + Left button rotates the manipulatedFrame(). -setMouseBinding(Qt::ALT + Qt::SHIFT + Qt::LeftButton, FRAME, ROTATE); +// Alt + Shift and Left button rotates the manipulatedFrame(). +setMouseBinding(Qt::AltModifier | Qt::ShiftModifier, Qt::LeftButton, FRAME, ROTATE); \endcode +If \p withConstraint is \c true (default), the possible +qglviewer::Frame::constraint() of the associated Frame will be enforced during motion. + The list of all possible MouseAction, some binding examples and default bindings are provided in the mouse page. See the keyboardAndMouse example for an illustration. -If no mouse button is specified in \p state, the binding is ignored. If an action was previously -associated with this \p state, it is silently overwritten (call mouseAction() before to know if this -\p state is already binded). +If no mouse button is specified, the binding is ignored. If an action was previously +associated with this keyboard and button combination, it is silently overwritten (call mouseAction() +before to check). -To remove a specific mouse binding, use code like: -\code -setMouseBinding(myButtonAndModifiersCombo, myHandler, NO_MOUSE_ACTION); -\endcode +To remove a specific mouse binding, use \p NO_MOUSE_ACTION as the \p action. -See also setMouseBinding(int, ClickAction, bool, int) and setWheelBinding(). */ -void QGLViewer::setMouseBinding(int state, MouseHandler handler, MouseAction action, bool withConstraint) +See also setMouseBinding(Qt::KeyboardModifiers, Qt::MouseButtons, ClickAction, bool, int), setWheelBinding() and clearMouseBindings(). */ +void QGLViewer::setMouseBinding(Qt::Key key, Qt::KeyboardModifiers modifiers, Qt::MouseButton button, MouseHandler handler, MouseAction action, bool withConstraint) { if ((handler == FRAME) && ((action == MOVE_FORWARD) || (action == MOVE_BACKWARD) || - (action == ROLL) || (action == LOOK_AROUND) || - (action == ZOOM_ON_REGION))) - { -#if QT_VERSION >= 0x040000 + (action == ROLL) || (action == LOOK_AROUND) || + (action == ZOOM_ON_REGION))) { qWarning("Cannot bind %s to FRAME", mouseActionString(action).toLatin1().constData()); -#else - qWarning("Cannot bind %s to FRAME", mouseActionString(action).latin1()); -#endif + return; + } + + if (button == Qt::NoButton) { + qWarning("No mouse button specified in setMouseBinding"); + return; } + + MouseActionPrivate map; + map.handler = handler; + map.action = action; + map.withConstraint = withConstraint; + + MouseBindingPrivate mbp(modifiers, button, key); + if (action == NO_MOUSE_ACTION) + mouseBinding_.remove(mbp); else - if ((state & Qt::MouseButtonMask) == 0) - qWarning("No mouse button specified in setMouseBinding"); - else - { - MouseActionPrivate map; - map.handler = handler; - map.action = action; - map.withConstraint = withConstraint; - state = convertToKeyboardModifiers(state); - - mouseBinding_.remove(state); - - if (action != NO_MOUSE_ACTION) - mouseBinding_.insert(state, map); - - ClickActionPrivate cap; - cap.modifiers = Qt::KeyboardModifiers(state & Qt::KeyboardModifierMask); - cap.button = Qt::MouseButtons(state & Qt::MouseButtonMask); - cap.doubleClick = false; - cap.buttonsBefore = Qt::NoButton; - clickBinding_.remove(cap); - } + mouseBinding_.insert(mbp, map); + + ClickBindingPrivate cbp(modifiers, button, false, Qt::NoButton, key); + clickBinding_.remove(cbp); } +#ifndef DOXYGEN +/*! This method is deprecated since version 2.5.0 -/*! Associates a ClickAction to any mouse buttons and keyboard modifiers combination. + Use setMouseBinding(Qt::KeyboardModifiers, Qt::MouseButtons, MouseHandler, MouseAction, bool) instead. +*/ +void QGLViewer::setMouseBinding(unsigned int state, ClickAction action, bool doubleClick, Qt::MouseButtons buttonsBefore) { + qWarning("setMouseBinding(int state, ClickAction...) is deprecated. Use the modifier/button equivalent"); + setMouseBinding(keyboardModifiersFromState(state), + mouseButtonFromState(state), + action, + doubleClick, + buttonsBefore); +} +#endif - This method has been deprecated in version 3. - Use setMouseBinding(Qt::KeyboardModifiers, Qt::MouseButtons, ClickAction, bool, Qt::MouseButtons) instead. - Replace the int \p state by a combination of Qt::KeyboardModifiers and Qt::MouseButtons. +/*! Defines a ClickAction binding. - For instance + Same as calling setMouseBinding(Qt::Key, Qt::KeyboardModifiers, Qt::MouseButton, ClickAction, bool, Qt::MouseButtons), + with a key value of Qt::Key(0) (i.e. no regular key needs to be pressed to activate this action). */ +void QGLViewer::setMouseBinding(Qt::KeyboardModifiers modifiers, Qt::MouseButton button, ClickAction action, bool doubleClick, Qt::MouseButtons buttonsBefore) +{ + setMouseBinding(Qt::Key(0), modifiers, button, action, doubleClick, buttonsBefore); +} + +/*! Associates a ClickAction to a button and keyboard key and modifier(s) combination. -The parameters should read: when the \p state mouse button(s) is (are) pressed (possibly with Alt, -Control or Shift modifiers or any combination of these), and possibly with a \p doubleClick, -perform \p action. +The parameters should read: when \p button is pressed, while the \p modifiers and \p key keys are down, +and possibly as a \p doubleClick, then perform \p action. Use Qt::NoModifier to indicate that no modifier +key is needed, and a \p key value of 0 if no regular key has to be pressed (or simply use +setMouseBinding(Qt::KeyboardModifiers, Qt::MouseButton, ClickAction, bool, Qt::MouseButtons)). -If \p buttonsBefore is specified (valid only when \p doubleClick is \c true), then this mouse -button(s) has to be pressed \e before the double click occurs in order to perform \p action. +If \p buttonsBefore is specified (valid only when \p doubleClick is \c true), then this (or these) other mouse +button(s) has (have) to be pressed \e before the double click occurs in order to execute \p action. The list of all possible ClickAction, some binding examples and default bindings are listed in the mouse page. See also the setMouseBinding() documentation. @@ -2978,33 +2629,42 @@ The list of all possible ClickAction, some binding examples and default bindings See the keyboardAndMouse example for an illustration. -The binding is ignored if no mouse button is specified in \p state. +The binding is ignored if Qt::NoButton is specified as \p buttons. -\note If you use Qt version 2 or 3, the \p buttonsBefore parameter is actually a Qt::ButtonState. */ -void QGLViewer::setMouseBinding(int state, ClickAction action, bool doubleClick, Qt::MouseButtons buttonsBefore) +See also setMouseBinding(Qt::KeyboardModifiers, Qt::MouseButtons, MouseHandler, MouseAction, bool), setWheelBinding() and clearMouseBindings(). +*/ +void QGLViewer::setMouseBinding(Qt::Key key, Qt::KeyboardModifiers modifiers, Qt::MouseButton button, ClickAction action, bool doubleClick, Qt::MouseButtons buttonsBefore) { - if ((buttonsBefore != Qt::NoButton) && !doubleClick) + if ((buttonsBefore != Qt::NoButton) && !doubleClick) { qWarning("Buttons before is only meaningful when doubleClick is true in setMouseBinding()."); + return; + } + + if (button == Qt::NoButton) { + qWarning("No mouse button specified in setMouseBinding"); + return; + } + + ClickBindingPrivate cbp(modifiers, button, doubleClick, buttonsBefore, key); + + // #CONNECTION performClickAction comment on NO_CLICK_ACTION + if (action == NO_CLICK_ACTION) + clickBinding_.remove(cbp); else - if ((state & Qt::MouseButtonMask) == 0) - qWarning("No mouse button specified in setMouseBinding"); - else - { - ClickActionPrivate cap; - state = convertToKeyboardModifiers(state); - cap.modifiers = Qt::KeyboardModifiers(state & Qt::KeyboardModifierMask); - cap.button = Qt::MouseButtons(state & Qt::MouseButtonMask); - cap.doubleClick = doubleClick; - cap.buttonsBefore = buttonsBefore; - clickBinding_.remove(cap); - - // #CONNECTION performClickAction comment on NO_CLICK_ACTION - if (action != NO_CLICK_ACTION) - clickBinding_.insert(cap, action); - - if ((!doubleClick) && (buttonsBefore == Qt::NoButton)) - mouseBinding_.remove(state); - } + clickBinding_.insert(cbp, action); + + if ((!doubleClick) && (buttonsBefore == Qt::NoButton)) { + MouseBindingPrivate mbp(modifiers, button, key); + mouseBinding_.remove(mbp); + } +} + +/*! Defines a mouse wheel binding. + + Same as calling setWheelBinding(Qt::Key, Qt::KeyboardModifiers, MouseHandler, MouseAction, bool), + with a key value of Qt::Key(0) (i.e. no regular key needs to be pressed to activate this action). */ +void QGLViewer::setWheelBinding(Qt::KeyboardModifiers modifiers, MouseHandler handler, MouseAction action, bool withConstraint) { + setWheelBinding(Qt::Key(0), modifiers, handler, action, withConstraint); } /*! Associates a MouseAction and a MouseHandler to a mouse wheel event. @@ -3017,235 +2677,363 @@ QGLViewer::CAMERA can receive QGLViewer::ZOOM and QGLViewer::MOVE_FORWARD. The difference between QGLViewer::ZOOM and QGLViewer::MOVE_FORWARD is that QGLViewer::ZOOM speed depends on the distance to the object, while QGLViewer::MOVE_FORWARD moves at a constant speed defined by qglviewer::Camera::flySpeed(). */ -void QGLViewer::setWheelBinding(Qt::KeyboardModifiers modifiers, MouseHandler handler, MouseAction action, bool withConstraint) +void QGLViewer::setWheelBinding(Qt::Key key, Qt::KeyboardModifiers modifiers, MouseHandler handler, MouseAction action, bool withConstraint) { //#CONNECTION# ManipulatedFrame::wheelEvent and ManipulatedCameraFrame::wheelEvent switches - if ((action != ZOOM) && (action != MOVE_FORWARD) && (action != MOVE_BACKWARD) && (action != NO_MOUSE_ACTION)) -#if QT_VERSION >= 0x040000 + if ((action != ZOOM) && (action != MOVE_FORWARD) && (action != MOVE_BACKWARD) && (action != NO_MOUSE_ACTION)) { qWarning("Cannot bind %s to wheel", mouseActionString(action).toLatin1().constData()); -#else - qWarning("Cannot bind %s to wheel", + mouseActionString(action).latin1()); -#endif + return; + } + + if ((handler == FRAME) && (action != ZOOM) && (action != NO_MOUSE_ACTION)) { + qWarning("Cannot bind %s to FRAME wheel", mouseActionString(action).toLatin1().constData()); + return; + } + + MouseActionPrivate map; + map.handler = handler; + map.action = action; + map.withConstraint = withConstraint; + + WheelBindingPrivate wbp(modifiers, key); + if (action == NO_MOUSE_ACTION) + wheelBinding_.remove(wbp); else - if ((handler == FRAME) && (action != ZOOM) && (action != NO_MOUSE_ACTION)) -#if QT_VERSION >= 0x040000 - qWarning("Cannot bind %s to FRAME wheel", mouseActionString(action).toLatin1().constData()); -#else - qWarning("Cannot bind %s to FRAME wheel", mouseActionString(action).latin1()); -#endif - else - { - MouseActionPrivate map; - map.handler = handler; - map.action = action; - map.withConstraint = withConstraint; - modifiers = convertKeyboardModifiers(modifiers); - wheelBinding_.remove(modifiers); - - if (action != NO_MOUSE_ACTION) - wheelBinding_.insert(modifiers, map); - } + wheelBinding_[wbp] = map; } -/*! Returns the MouseAction associated with the \p state mouse button(s) and keyboard modifiers. -Returns QGLViewer::NO_MOUSE_ACTION if no action is associated. +/*! Clears all the default mouse bindings. + +After this call, you will have to use setMouseBinding() and setWheelBinding() to restore the mouse bindings you are interested in. +*/ +void QGLViewer::clearMouseBindings() { + mouseBinding_.clear(); + clickBinding_.clear(); + wheelBinding_.clear(); +} + +/*! Clears all the default keyboard shortcuts. + +After this call, you will have to use setShortcut() to define your own keyboard shortcuts. +*/ +void QGLViewer::clearShortcuts() { + keyboardBinding_.clear(); + pathIndex_.clear(); +} + +/*! This method is deprecated since version 2.5.0 + + Use mouseAction(Qt::Key, Qt::KeyboardModifiers, Qt::MouseButtons) instead. +*/ +QGLViewer::MouseAction QGLViewer::mouseAction(unsigned int state) const { + qWarning("mouseAction(int state,...) is deprecated. Use the modifier/button equivalent"); + return mouseAction(Qt::Key(0), keyboardModifiersFromState(state), mouseButtonFromState(state)); +} + +/*! Returns the MouseAction the will be triggered when the mouse \p button is pressed, +while the keyboard \p modifiers and \p key are pressed. + +Returns QGLViewer::NO_MOUSE_ACTION if no action is associated with this combination. Use 0 for \p key +to indicate that no regular key needs to be pressed. For instance, to know which motion corresponds to Alt+LeftButton, do: \code -QGLViewer::MouseAction ma = mouseAction(Qt::ALT + Qt::LeftButton); +QGLViewer::MouseAction ma = mouseAction(0, Qt::AltModifier, Qt::LeftButton); if (ma != QGLViewer::NO_MOUSE_ACTION) ... \endcode -Use mouseHandler() to know which object (QGLViewer::CAMERA or QGLViewer::FRAME) will perform this +Use mouseHandler() to know which object (QGLViewer::CAMERA or QGLViewer::FRAME) will execute this action. */ -QGLViewer::MouseAction QGLViewer::mouseAction(int state) const +QGLViewer::MouseAction QGLViewer::mouseAction(Qt::Key key, Qt::KeyboardModifiers modifiers, Qt::MouseButton button) const { - state = convertToKeyboardModifiers(state); - if (mouseBinding_.contains(state)) - return mouseBinding_[state].action; + MouseBindingPrivate mbp(modifiers, button, key); + if (mouseBinding_.contains(mbp)) + return mouseBinding_[mbp].action; else return NO_MOUSE_ACTION; } -/*! Returns the MouseHandler associated with the \p state. If no action is -associated, returns \c -1. +/*! This method is deprecated since version 2.5.0 + + Use mouseHanler(Qt::Key, Qt::KeyboardModifiers, Qt::MouseButtons) instead. +*/ +int QGLViewer::mouseHandler(unsigned int state) const { + qWarning("mouseHandler(int state,...) is deprecated. Use the modifier/button equivalent"); + return mouseHandler(Qt::Key(0), keyboardModifiersFromState(state), mouseButtonFromState(state)); +} + +/*! Returns the MouseHandler which will be activated when the mouse \p button is pressed, while the \p modifiers and \p key are pressed. + +If no action is associated with this combination, returns \c -1. Use 0 for \p key and Qt::NoModifier for \p modifiers +to represent the lack of a key press. For instance, to know which handler receives the Alt+LeftButton, do: \code -int mh = mouseHandler(Qt::ALT + Qt::LeftButton); +int mh = mouseHandler(0, Qt::AltModifier, Qt::LeftButton); if (mh == QGLViewer::CAMERA) ... \endcode -Use mouseAction() to know which action (see the MouseAction enum) will be perform on this handler. */ -int QGLViewer::mouseHandler(int state) const +Use mouseAction() to know which action (see the MouseAction enum) will be performed on this handler. */ +int QGLViewer::mouseHandler(Qt::Key key, Qt::KeyboardModifiers modifiers, Qt::MouseButton button) const { - state = convertToKeyboardModifiers(state); - if (mouseBinding_.contains(state)) - return mouseBinding_[state].handler; + MouseBindingPrivate mbp(modifiers, button, key); + if (mouseBinding_.contains(mbp)) + return mouseBinding_[mbp].handler; else return -1; } -/*! Returns the mouse buttons and keyboard modifiers (if any) that have to be used to activate \p -action on \p handler (with constraint or not). -If no state triggers the action, returns Qt::NoButton which is an impossible case since at least -one mouse button has to be specified in setMouseBinding(). +#ifndef DOXYGEN +/*! This method is deprecated since version 2.5.0 -To know which keys and mouse buttons have to be pressed to translate the camera, use tests like: -\code -int bs = mouseButtonState(QGLViewer::CAMERA, QGLViewer::TRANSLATE); -if (bs & Qt::RightButton) ... // Right button needed to translate the camera -if (bs & Qt::AltModifier) ... // Alt key needed (use AltModifier with Qt version 2 or 3) -if (bs & Qt::KeyboardModifierMask == Qt::NoButton) ... // No keyboard modifier needed -\endcode + Use mouseButtons() and keyboardModifiers() instead. +*/ +int QGLViewer::mouseButtonState(MouseHandler handler, MouseAction action, bool withConstraint) const { + qWarning("mouseButtonState() is deprecated. Use mouseButtons() and keyboardModifiers() instead"); + for (QMap::ConstIterator it=mouseBinding_.begin(), end=mouseBinding_.end(); it != end; ++it) + if ( (it.value().handler == handler) && (it.value().action == action) && (it.value().withConstraint == withConstraint) ) + return (int) it.key().modifiers | (int) it.key().button; + + return Qt::NoButton; +} +#endif -Note that mouse bindings are displayed in the 'Mouse' help window tab. +/*! Returns the keyboard state that triggers \p action on \p handler \p withConstraint using the mouse wheel. -See also mouseAction() and mouseHandler(). */ -int QGLViewer::mouseButtonState(MouseHandler handler, MouseAction action, bool withConstraint) const +If such a binding exists, results are stored in the \p key and \p modifiers +parameters. If the MouseAction \p action is not bound, \p key is set to the illegal -1 value. +If several keyboard states trigger the MouseAction, one of them is returned. + +See also setMouseBinding(), getClickActionBinding() and getMouseActionBinding(). */ +void QGLViewer::getWheelActionBinding(MouseHandler handler, MouseAction action, bool withConstraint, + Qt::Key& key, Qt::KeyboardModifiers& modifiers) const { - for (QMap::ConstIterator it=mouseBinding_.begin(), end=mouseBinding_.end(); it != end; ++it) - if ( (it.value().handler == handler) && (it.value().action == action) && (it.value().withConstraint == withConstraint) ) - return it.key(); + for (QMap::ConstIterator it=wheelBinding_.begin(), end=wheelBinding_.end(); it != end; ++it) + if ( (it.value().handler == handler) && (it.value().action == action) && (it.value().withConstraint == withConstraint) ) { + key = it.key().key; + modifiers = it.key().modifiers; + return; + } - return Qt::NoButton; + key = Qt::Key(-1); + modifiers = Qt::NoModifier; +} + +/*! Returns the mouse and keyboard state that triggers \p action on \p handler \p withConstraint. + +If such a binding exists, results are stored in the \p key, \p modifiers and \p button +parameters. If the MouseAction \p action is not bound, \p button is set to \c Qt::NoButton. +If several mouse and keyboard states trigger the MouseAction, one of them is returned. + +See also setMouseBinding(), getClickActionBinding() and getWheelActionBinding(). */ +void QGLViewer::getMouseActionBinding(MouseHandler handler, MouseAction action, bool withConstraint, + Qt::Key& key, Qt::KeyboardModifiers& modifiers, Qt::MouseButton& button) const +{ + for (QMap::ConstIterator it=mouseBinding_.begin(), end=mouseBinding_.end(); it != end; ++it) { + if ( (it.value().handler == handler) && (it.value().action == action) && (it.value().withConstraint == withConstraint) ) { + key = it.key().key; + modifiers = it.key().modifiers; + button = it.key().button; + return; + } + } + + key = Qt::Key(0); + modifiers = Qt::NoModifier; + button = Qt::NoButton; } -/*! Same as mouseAction(), but for the wheel action. +/*! Returns the MouseAction (if any) that is performed when using the wheel, when the \p modifiers and \p key keyboard keys are pressed. -\note If you use Qt version 2 or 3, \p modifiers is actually a \c Qt::ButtonState. The \c Modifier -postfix is replaced by \c Button in the enums' names (\c Qt::ControlButton, \c Qt::AltButton, -Qt::ShiftButton, Qt::MetaButton). */ -QGLViewer::MouseAction QGLViewer::wheelAction(Qt::KeyboardModifiers modifiers) const +Returns NO_MOUSE_ACTION if no such binding has been defined using setWheelBinding(). + +Same as mouseAction(), but for the wheel action. See also wheelHandler(). +*/ +QGLViewer::MouseAction QGLViewer::wheelAction(Qt::Key key, Qt::KeyboardModifiers modifiers) const { - modifiers = convertKeyboardModifiers(modifiers); - if (wheelBinding_.contains(modifiers)) - return wheelBinding_[modifiers].action; + WheelBindingPrivate wbp(modifiers, key); + if (wheelBinding_.contains(wbp)) + return wheelBinding_[wbp].action; else return NO_MOUSE_ACTION; } -/*! Same as mouseHandler() but for the wheel action. See also wheelAction(). */ -int QGLViewer::wheelHandler(Qt::KeyboardModifiers modifiers) const +/*! Returns the MouseHandler (if any) that receives wheel events when the \p modifiers and \p key keyboard keys are pressed. + + Returns -1 if no no such binding has been defined using setWheelBinding(). See also wheelAction(). +*/ +int QGLViewer::wheelHandler(Qt::Key key, Qt::KeyboardModifiers modifiers) const { - modifiers = convertKeyboardModifiers(modifiers); - if (wheelBinding_.contains(modifiers)) - return wheelBinding_[modifiers].handler; + WheelBindingPrivate wbp(modifiers, key); + if (wheelBinding_.contains(wbp)) + return wheelBinding_[wbp].handler; else return -1; } -/*! Same as mouseButtonState(), but for the wheel. +/*! Same as mouseAction(), but for the ClickAction set using setMouseBinding(). + +Returns NO_CLICK_ACTION if no click action is associated with this keyboard and mouse buttons combination. */ +QGLViewer::ClickAction QGLViewer::clickAction(Qt::Key key, Qt::KeyboardModifiers modifiers, Qt::MouseButton button, + bool doubleClick, Qt::MouseButtons buttonsBefore) const { + ClickBindingPrivate cbp(modifiers, button, doubleClick, buttonsBefore, key); + if (clickBinding_.contains(cbp)) + return clickBinding_[cbp]; + else + return NO_CLICK_ACTION; +} + +#ifndef DOXYGEN +/*! This method is deprecated since version 2.5.0 -\attention Returns -1 when no Qt::ButtonState was associated with this \p handler/ \p action/ \p -withConstraint combination (mouseButtonState() would return Qt::NoButton instead). */ -int QGLViewer::wheelButtonState(MouseHandler handler, MouseAction action, bool withConstraint) const + Use wheelAction(Qt::Key key, Qt::KeyboardModifiers modifiers) instead. */ +QGLViewer::MouseAction QGLViewer::wheelAction(Qt::KeyboardModifiers modifiers) const { + qWarning("wheelAction() is deprecated. Use the new wheelAction() method with a key parameter instead"); + return wheelAction(Qt::Key(0), modifiers); +} + +/*! This method is deprecated since version 2.5.0 + + Use wheelHandler(Qt::Key key, Qt::KeyboardModifiers modifiers) instead. */ +int QGLViewer::wheelHandler(Qt::KeyboardModifiers modifiers) const { + qWarning("wheelHandler() is deprecated. Use the new wheelHandler() method with a key parameter instead"); + return wheelHandler(Qt::Key(0), modifiers); +} + +/*! This method is deprecated since version 2.5.0 + + Use wheelAction() and wheelHandler() instead. */ +unsigned int QGLViewer::wheelButtonState(MouseHandler handler, MouseAction action, bool withConstraint) const { - for (QMap::ConstIterator it=wheelBinding_.begin(), end=wheelBinding_.end(); it!=end; ++it) + qWarning("wheelButtonState() is deprecated. Use the wheelAction() and wheelHandler() instead"); + for (QMap::ConstIterator it=wheelBinding_.begin(), end=wheelBinding_.end(); it!=end; ++it) if ( (it.value().handler == handler) && (it.value().action == action) && (it.value().withConstraint == withConstraint) ) - return it.key(); + return it.key().key + it.key().modifiers; return -1; } -/*! Same as mouseAction(), but for the ClickAction set using setMouseBinding(). */ -QGLViewer::ClickAction QGLViewer::clickAction(int state, bool doubleClick, Qt::MouseButtons buttonsBefore) const -{ - ClickActionPrivate cap; - cap.modifiers = Qt::KeyboardModifiers(convertToKeyboardModifiers(state) & Qt::KeyboardModifierMask); - cap.button = Qt::MouseButtons(state & Qt::MouseButtonMask); - cap.doubleClick = doubleClick; - cap.buttonsBefore = buttonsBefore; - if (clickBinding_.contains(cap)) - return clickBinding_[cap]; - else - return NO_CLICK_ACTION; +/*! This method is deprecated since version 2.5.0 + + Use clickAction(Qt::KeyboardModifiers, Qt::MouseButtons, bool, Qt::MouseButtons) instead. +*/ +QGLViewer::ClickAction QGLViewer::clickAction(unsigned int state, bool doubleClick, Qt::MouseButtons buttonsBefore) const { + qWarning("clickAction(int state,...) is deprecated. Use the modifier/button equivalent"); + return clickAction(Qt::Key(0), + keyboardModifiersFromState(state), + mouseButtonFromState(state), + doubleClick, + buttonsBefore); } -/*! Similar to mouseButtonState(), but for ClickAction. +/*! This method is deprecated since version 2.5.0 -The results of the query are returned in the \p state, \p doubleClick and \p buttonsBefore -parameters. If the ClickAction is not associated to any mouse button, \c Qt::NoButton is returned -in \p state. If several mouse buttons trigger in the ClickAction, one of them is returned. */ -void QGLViewer::getClickButtonState(ClickAction ca, int& state, bool& doubleClick, Qt::MouseButtons& buttonsBefore) const + Use getClickActionState(ClickAction, Qt::Key, Qt::KeyboardModifiers, Qt::MouseButton, bool, Qt::MouseButtons) instead. +*/ +void QGLViewer::getClickButtonState(ClickAction action, unsigned int& state, bool& doubleClick, Qt::MouseButtons& buttonsBefore) const { + qWarning("getClickButtonState(int state,...) is deprecated. Use the modifier/button equivalent"); + Qt::KeyboardModifiers modifiers; + Qt::MouseButton button; + Qt::Key key; + getClickActionBinding(action, key, modifiers, button, doubleClick, buttonsBefore); + state = (unsigned int) modifiers | (unsigned int) button | (unsigned int) key; +} +#endif + +/*! Returns the mouse and keyboard state that triggers \p action. + +If such a binding exists, results are stored in the \p key, \p modifiers, \p button, \p doubleClick and \p buttonsBefore +parameters. If the ClickAction \p action is not bound, \p button is set to \c Qt::NoButton. +If several mouse buttons trigger in the ClickAction, one of them is returned. + +See also setMouseBinding(), getMouseActionBinding() and getWheelActionBinding(). */ +void QGLViewer::getClickActionBinding(ClickAction action, Qt::Key& key, Qt::KeyboardModifiers& modifiers, Qt::MouseButton &button, bool& doubleClick, Qt::MouseButtons& buttonsBefore) const { - for (QMap::ConstIterator it=clickBinding_.begin(), end=clickBinding_.end(); it != end; ++it) - if (it.value() == ca) - { - state = it.key().modifiers | it.key().button; + for (QMap::ConstIterator it=clickBinding_.begin(), end=clickBinding_.end(); it != end; ++it) + if (it.value() == action) { + modifiers = it.key().modifiers; + button = it.key().button; doubleClick = it.key().doubleClick; buttonsBefore = it.key().buttonsBefore; + key = it.key().key; return; } - state = Qt::NoButton; + modifiers = Qt::NoModifier; + button = Qt::NoButton; + doubleClick = false; + buttonsBefore = Qt::NoButton; + key = Qt::Key(0); } /*! This function should be used in conjunction with toggleCameraMode(). It returns \c true when at -least one mouse button is binded to the \c REVOLVE mouseAction. This is crude way of determining +least one mouse button is binded to the \c ROTATE mouseAction. This is crude way of determining which "mode" the camera is in. */ -bool QGLViewer::cameraIsInRevolveMode() const +bool QGLViewer::cameraIsInRotateMode() const { //#CONNECTION# used in toggleCameraMode() and keyboardString() - return mouseButtonState(CAMERA, ROTATE) != Qt::NoButton; + Qt::Key key; + Qt::KeyboardModifiers modifiers; + Qt::MouseButton button; + getMouseActionBinding(CAMERA, ROTATE, true /*constraint*/, key, modifiers, button); + return button != Qt::NoButton; } /*! Swaps between two predefined camera mouse bindings. The first mode makes the camera observe the scene while revolving around the -qglviewer::Camera::revolveAroundPoint(). The second mode is designed for walkthrough applications +qglviewer::Camera::pivotPoint(). The second mode is designed for walkthrough applications and simulates a flying camera. Practically, the three mouse buttons are respectively binded to: -\arg In revolve mode: QGLViewer::ROTATE, QGLViewer::ZOOM, QGLViewer::TRANSLATE. +\arg In rotate mode: QGLViewer::ROTATE, QGLViewer::ZOOM, QGLViewer::TRANSLATE. \arg In fly mode: QGLViewer::MOVE_FORWARD, QGLViewer::LOOK_AROUND, QGLViewer::MOVE_BACKWARD. The current mode is determined by checking if a mouse button is binded to QGLViewer::ROTATE for -the QGLViewer::CAMERA (using mouseButtonState()). The state key that was previously used to move -the camera is preserved. */ +the QGLViewer::CAMERA. The state key that was previously used to move the camera is preserved. */ void QGLViewer::toggleCameraMode() { - bool revolveMode = cameraIsInRevolveMode(); - int bs; - if (revolveMode) - bs = mouseButtonState(CAMERA, ROTATE); - else - bs = mouseButtonState(CAMERA, MOVE_FORWARD); - Qt::KeyboardModifiers modifiers = Qt::KeyboardModifiers(bs & Qt::KeyboardModifierMask); + Qt::Key key; + Qt::KeyboardModifiers modifiers; + Qt::MouseButton button; + getMouseActionBinding(CAMERA, ROTATE, true /*constraint*/, key, modifiers, button); + bool rotateMode = button != Qt::NoButton; + + if (!rotateMode) { + getMouseActionBinding(CAMERA, MOVE_FORWARD, true /*constraint*/, key, modifiers, button); + } //#CONNECTION# setDefaultMouseBindings() - if (revolveMode) + if (rotateMode) { - camera()->frame()->updateFlyUpVector(); + camera()->frame()->updateSceneUpVector(); camera()->frame()->stopSpinning(); - setMouseBinding(modifiers | Qt::LeftButton, CAMERA, MOVE_FORWARD); - setMouseBinding(modifiers | Qt::MidButton, CAMERA, LOOK_AROUND); - setMouseBinding(modifiers | Qt::RightButton, CAMERA, MOVE_BACKWARD); + setMouseBinding(modifiers, Qt::LeftButton, CAMERA, MOVE_FORWARD); + setMouseBinding(modifiers, Qt::MidButton, CAMERA, LOOK_AROUND); + setMouseBinding(modifiers, Qt::RightButton, CAMERA, MOVE_BACKWARD); - setMouseBinding(modifiers | Qt::LeftButton | Qt::MidButton, CAMERA, ROLL); - // 2.2.4 setMouseBinding(modifiers | Qt::RightButton | Qt::MidButton, CAMERA, SCREEN_TRANSLATE); + setMouseBinding(Qt::Key_R, modifiers, Qt::LeftButton, CAMERA, ROLL); - setMouseBinding(Qt::LeftButton, NO_CLICK_ACTION, true); - setMouseBinding(Qt::MidButton, NO_CLICK_ACTION, true); - setMouseBinding(Qt::RightButton, NO_CLICK_ACTION, true); + setMouseBinding(Qt::NoModifier, Qt::LeftButton, NO_CLICK_ACTION, true); + setMouseBinding(Qt::NoModifier, Qt::MidButton, NO_CLICK_ACTION, true); + setMouseBinding(Qt::NoModifier, Qt::RightButton, NO_CLICK_ACTION, true); setWheelBinding(modifiers, CAMERA, MOVE_FORWARD); } else { // Should stop flyTimer. But unlikely and not easy. - setMouseBinding(modifiers | Qt::LeftButton, CAMERA, ROTATE); - setMouseBinding(modifiers | Qt::MidButton, CAMERA, ZOOM); - setMouseBinding(modifiers | Qt::RightButton, CAMERA, TRANSLATE); + setMouseBinding(modifiers, Qt::LeftButton, CAMERA, ROTATE); + setMouseBinding(modifiers, Qt::MidButton, CAMERA, ZOOM); + setMouseBinding(modifiers, Qt::RightButton, CAMERA, TRANSLATE); - setMouseBinding(modifiers | Qt::LeftButton | Qt::MidButton, CAMERA, SCREEN_ROTATE); - // 2.2.4 setMouseBinding(modifiers | Qt::RightButton | Qt::MidButton, CAMERA, SCREEN_TRANSLATE); + setMouseBinding(Qt::Key_R, modifiers, Qt::LeftButton, CAMERA, SCREEN_ROTATE); - setMouseBinding(Qt::LeftButton, ALIGN_CAMERA, true); - setMouseBinding(Qt::MidButton, SHOW_ENTIRE_SCENE, true); - setMouseBinding(Qt::RightButton, CENTER_SCENE, true); + setMouseBinding(Qt::NoModifier, Qt::LeftButton, ALIGN_CAMERA, true); + setMouseBinding(Qt::NoModifier, Qt::MidButton, SHOW_ENTIRE_SCENE, true); + setMouseBinding(Qt::NoModifier, Qt::RightButton, CENTER_SCENE, true); setWheelBinding(modifiers, CAMERA, ZOOM); } @@ -3274,23 +3062,23 @@ void QGLViewer::setManipulatedFrame(ManipulatedFrame* frame) if (manipulatedFrame() != camera()->frame()) { - disconnect(manipulatedFrame(), SIGNAL(manipulated()), this, SLOT(updateGL())); - disconnect(manipulatedFrame(), SIGNAL(spun()), this, SLOT(updateGL())); + disconnect(manipulatedFrame(), SIGNAL(manipulated()), this, SLOT(update())); + disconnect(manipulatedFrame(), SIGNAL(spun()), this, SLOT(update())); } } manipulatedFrame_ = frame; manipulatedFrameIsACamera_ = ((manipulatedFrame() != camera()->frame()) && - (dynamic_cast(manipulatedFrame()) != NULL)); + (dynamic_cast(manipulatedFrame()) != NULL)); if (manipulatedFrame()) { // Prevent multiple connections, that would result in useless display updates if (manipulatedFrame() != camera()->frame()) { - connect(manipulatedFrame(), SIGNAL(manipulated()), SLOT(updateGL())); - connect(manipulatedFrame(), SIGNAL(spun()), SLOT(updateGL())); + connect(manipulatedFrame(), SIGNAL(manipulated()), SLOT(update())); + connect(manipulatedFrame(), SIGNAL(spun()), SLOT(update())); } } } @@ -3301,9 +3089,9 @@ void QGLViewer::setManipulatedFrame(ManipulatedFrame* frame) //////////////////////////////////////////////////////////////////////////////// /*! Draws viewer related visual hints. -Displays the new qglviewer::Camera::revolveAroundPoint() when it is changed. See the mouse page for details. Also draws a line between -qglviewer::Camera::revolveAroundPoint() and mouse cursor when the camera is rotated around the +qglviewer::Camera::pivotPoint() and mouse cursor when the camera is rotated around the camera Z axis. See also setVisualHintsMask() and resetVisualHints(). The hint color is foregroundColor(). @@ -3316,20 +3104,20 @@ Limitation : One needs to have access to visualHint_ to overload this method. Removed from the documentation for this reason. */ void QGLViewer::drawVisualHints() { - // Revolve Around point cross + // Pivot point cross if (visualHint_ & 1) { - const float size = 15.0; - Vec proj = camera()->projectedCoordinatesOf(camera()->revolveAroundPoint()); + const qreal size = 15.0; + Vec proj = camera()->projectedCoordinatesOf(camera()->pivotPoint()); startScreenCoordinatesSystem(); glDisable(GL_LIGHTING); glDisable(GL_DEPTH_TEST); glLineWidth(3.0); glBegin(GL_LINES); - glVertex2f(proj.x - size, proj.y); - glVertex2f(proj.x + size, proj.y); - glVertex2f(proj.x, proj.y - size); - glVertex2f(proj.x, proj.y + size); + glVertex2d(proj.x - size, proj.y); + glVertex2d(proj.x + size, proj.y); + glVertex2d(proj.x, proj.y - size); + glVertex2d(proj.x, proj.y + size); glEnd(); glEnable(GL_DEPTH_TEST); stopScreenCoordinatesSystem(); @@ -3344,13 +3132,13 @@ void QGLViewer::drawVisualHints() if (camera()->frame()->action_ == SCREEN_ROTATE) { mf = camera()->frame(); - pnt = camera()->revolveAroundPoint(); + pnt = camera()->pivotPoint(); } if (manipulatedFrame() && (manipulatedFrame()->action_ == SCREEN_ROTATE)) { mf = manipulatedFrame(); // Maybe useful if the mf is a manipCameraFrame... - // pnt = manipulatedFrame()->revolveAroundPoint(); + // pnt = manipulatedFrame()->pivotPoint(); pnt = manipulatedFrame()->position(); } @@ -3362,8 +3150,8 @@ void QGLViewer::drawVisualHints() glDisable(GL_DEPTH_TEST); glLineWidth(3.0); glBegin(GL_LINES); - glVertex2f(pnt.x, pnt.y); - glVertex2f(mf->prevPos_.x(), mf->prevPos_.y()); + glVertex2d(pnt.x, pnt.y); + glVertex2i(mf->prevPos_.x(), mf->prevPos_.y()); glEnd(); glEnable(GL_DEPTH_TEST); stopScreenCoordinatesSystem(); @@ -3388,7 +3176,7 @@ void QGLViewer::drawVisualHints() } /*! Defines the mask that will be used to drawVisualHints(). The only available mask is currently 1, -corresponding to the display of the qglviewer::Camera::revolveAroundPoint(). resetVisualHints() is +corresponding to the display of the qglviewer::Camera::pivotPoint(). resetVisualHints() is automatically called after \p delay milliseconds (default is 2 seconds). */ void QGLViewer::setVisualHintsMask(int mask, int delay) { @@ -3412,34 +3200,34 @@ void QGLViewer::resetVisualHints() \p length, \p radius and \p nbSubdivisions define its geometry. If \p radius is negative (default), it is set to 0.05 * \p length. -Use drawArrow(const Vec& from, const Vec& to, float radius, int nbSubdivisions) or change the \c +Use drawArrow(const Vec& from, const Vec& to, qreal radius, int nbSubdivisions) or change the \c ModelView matrix to place the arrow in 3D. Uses current color and does not modify the OpenGL state. */ -void QGLViewer::drawArrow(float length, float radius, int nbSubdivisions) +void QGLViewer::drawArrow(qreal length, qreal radius, int nbSubdivisions) { static GLUquadric* quadric = gluNewQuadric(); if (radius < 0.0) radius = 0.05 * length; - const float head = 2.5*(radius / length) + 0.1; - const float coneRadiusCoef = 4.0 - 5.0 * head; + const qreal head = 2.5*(radius / length) + 0.1; + const qreal coneRadiusCoef = 4.0 - 5.0 * head; gluCylinder(quadric, radius, radius, length * (1.0 - head/coneRadiusCoef), nbSubdivisions, 1); - glTranslatef(0.0, 0.0, length * (1.0 - head)); + glTranslated(0.0, 0.0, length * (1.0 - head)); gluCylinder(quadric, coneRadiusCoef * radius, 0.0, head * length, nbSubdivisions, 1); - glTranslatef(0.0, 0.0, -length * (1.0 - head)); + glTranslated(0.0, 0.0, -length * (1.0 - head)); } /*! Draws a 3D arrow between the 3D point \p from and the 3D point \p to, both defined in the current ModelView coordinates system. -See drawArrow(float length, float radius, int nbSubdivisions) for details. */ -void QGLViewer::drawArrow(const Vec& from, const Vec& to, float radius, int nbSubdivisions) +See drawArrow(qreal length, qreal radius, int nbSubdivisions) for details. */ +void QGLViewer::drawArrow(const Vec& from, const Vec& to, qreal radius, int nbSubdivisions) { glPushMatrix(); - glTranslatef(from[0],from[1],from[2]); + glTranslated(from[0], from[1], from[2]); const Vec dir = to-from; glMultMatrixd(Quaternion(Vec(0,0,1), dir).matrix()); QGLViewer::drawArrow(dir.norm(), radius, nbSubdivisions); @@ -3464,11 +3252,11 @@ the three arrows. The OpenGL state is not modified by this method. axisIsDrawn() uses this method to draw a representation of the world coordinate system. See also QGLViewer::drawArrow() and QGLViewer::drawGrid(). */ -void QGLViewer::drawAxis(float length) +void QGLViewer::drawAxis(qreal length) { - const float charWidth = length / 40.0; - const float charHeight = length / 30.0; - const float charShift = 1.04 * length; + const qreal charWidth = length / 40.0; + const qreal charHeight = length / 30.0; + const qreal charShift = 1.04 * length; GLboolean lighting, colorMaterial; glGetBooleanv(GL_LIGHTING, &lighting); @@ -3478,24 +3266,24 @@ void QGLViewer::drawAxis(float length) glBegin(GL_LINES); // The X - glVertex3f(charShift, charWidth, -charHeight); - glVertex3f(charShift, -charWidth, charHeight); - glVertex3f(charShift, -charWidth, -charHeight); - glVertex3f(charShift, charWidth, charHeight); + glVertex3d(charShift, charWidth, -charHeight); + glVertex3d(charShift, -charWidth, charHeight); + glVertex3d(charShift, -charWidth, -charHeight); + glVertex3d(charShift, charWidth, charHeight); // The Y - glVertex3f( charWidth, charShift, charHeight); - glVertex3f(0.0, charShift, 0.0); - glVertex3f(-charWidth, charShift, charHeight); - glVertex3f(0.0, charShift, 0.0); - glVertex3f(0.0, charShift, 0.0); - glVertex3f(0.0, charShift, -charHeight); + glVertex3d( charWidth, charShift, charHeight); + glVertex3d(0.0, charShift, 0.0); + glVertex3d(-charWidth, charShift, charHeight); + glVertex3d(0.0, charShift, 0.0); + glVertex3d(0.0, charShift, 0.0); + glVertex3d(0.0, charShift, -charHeight); // The Z - glVertex3f(-charWidth, charHeight, charShift); - glVertex3f( charWidth, charHeight, charShift); - glVertex3f( charWidth, charHeight, charShift); - glVertex3f(-charWidth, -charHeight, charShift); - glVertex3f(-charWidth, -charHeight, charShift); - glVertex3f( charWidth, -charHeight, charShift); + glVertex3d(-charWidth, charHeight, charShift); + glVertex3d( charWidth, charHeight, charShift); + glVertex3d( charWidth, charHeight, charShift); + glVertex3d(-charWidth, -charHeight, charShift); + glVertex3d(-charWidth, -charHeight, charShift); + glVertex3d( charWidth, -charHeight, charShift); glEnd(); glEnable(GL_LIGHTING); @@ -3509,14 +3297,14 @@ void QGLViewer::drawAxis(float length) color[0] = 1.0f; color[1] = 0.7f; color[2] = 0.7f; color[3] = 1.0f; glMaterialfv(GL_FRONT_AND_BACK, GL_AMBIENT_AND_DIFFUSE, color); glPushMatrix(); - glRotatef(90.0, 0.0, 1.0, 0.0); + glRotatef(90.0f, 0.0f, 1.0f, 0.0f); QGLViewer::drawArrow(length, 0.01*length); glPopMatrix(); color[0] = 0.7f; color[1] = 1.0f; color[2] = 0.7f; color[3] = 1.0f; glMaterialfv(GL_FRONT_AND_BACK, GL_AMBIENT_AND_DIFFUSE, color); glPushMatrix(); - glRotatef(-90.0, 1.0, 0.0, 0.0); + glRotatef(-90.0f, 1.0f, 0.0f, 0.0f); QGLViewer::drawArrow(length, 0.01*length); glPopMatrix(); @@ -3532,7 +3320,7 @@ void QGLViewer::drawAxis(float length) place and orientate the grid in 3D space (see the drawAxis() documentation). The OpenGL state is not modified by this method. */ -void QGLViewer::drawGrid(float size, int nbSubdivisions) +void QGLViewer::drawGrid(qreal size, int nbSubdivisions) { GLboolean lighting; glGetBooleanv(GL_LIGHTING, &lighting); @@ -3542,11 +3330,11 @@ void QGLViewer::drawGrid(float size, int nbSubdivisions) glBegin(GL_LINES); for (int i=0; i<=nbSubdivisions; ++i) { - const float pos = size*(2.0*i/nbSubdivisions-1.0); - glVertex2f(pos, -size); - glVertex2f(pos, +size); - glVertex2f(-size, pos); - glVertex2f( size, pos); + const qreal pos = size*(2.0*i/nbSubdivisions-1.0); + glVertex2d(pos, -size); + glVertex2d(pos, +size); + glVertex2d(-size, pos); + glVertex2d( size, pos); } glEnd(); @@ -3561,14 +3349,8 @@ void QGLViewer::drawGrid(float size, int nbSubdivisions) /*! saveStateToFile() is called on all the QGLViewers using the QGLViewerPool(). */ void QGLViewer::saveStateToFileForAllViewers() { -#if QT_VERSION >= 0x040000 Q_FOREACH (QGLViewer* viewer, QGLViewer::QGLViewerPool()) { -#else - QPtrListIterator it(QGLViewer::QGLViewerPool()); - for (QGLViewer* viewer; (viewer = it.current()) != 0; ++it) - { -#endif if (viewer) viewer->saveStateToFile(); } @@ -3598,22 +3380,10 @@ QString QGLViewer::stateFileName() const if (!name.isEmpty() && QGLViewer::QGLViewerIndex(this) > 0) { QFileInfo fi(name); -#if QT_VERSION >= 0x040000 if (fi.suffix().isEmpty()) -#else - if (fi.extension(false).isEmpty()) -#endif name += QString::number(QGLViewer::QGLViewerIndex(this)); else -#if QT_VERSION >= 0x040000 name = fi.absolutePath() + '/' + fi.completeBaseName() + QString::number(QGLViewer::QGLViewerIndex(this)) + "." + fi.suffix(); -#else -# if QT_VERSION >= 0x030000 - name = fi.dirPath() + '/' + fi.baseName(true) + QString::number(QGLViewer::QGLViewerIndex(this)) + "." + fi.extension(false); -# else - name = fi.dirPath() + '/' + fi.baseName() + QString::number(QGLViewer::QGLViewerIndex(this)) + "." + fi.extension(); -# endif -#endif } return name; @@ -3641,19 +3411,11 @@ void QGLViewer::saveStateToFile() return; } -#if QT_VERSION >= 0x040000 const QString dirName = fileInfo.absolutePath(); -#else - const QString dirName = fileInfo.dirPath(); -#endif if (!QFileInfo(dirName).exists()) { QDir dir; -#if QT_VERSION >= 0x040000 if (!(dir.mkdir(dirName))) -#else - if (!(dir.mkdir(dirName, true))) -#endif { QMessageBox::warning(this, tr("Save to file error", "Message box window title"), tr("Unable to create directory %1").arg(dirName)); return; @@ -3662,11 +3424,7 @@ void QGLViewer::saveStateToFile() // Write the DOM tree to file QFile f(name); -#if QT_VERSION >= 0x040000 if (f.open(QIODevice::WriteOnly)) -#else - if (f.open(IO_WriteOnly)) -#endif { QTextStream out(&f); QDomDocument doc("QGLVIEWER"); @@ -3676,11 +3434,7 @@ void QGLViewer::saveStateToFile() f.close(); } else -#if QT_VERSION < 0x030200 - QMessageBox::warning(this, tr("Save to file error", "Message box window title"), tr("Unable to save to file %1").arg(name)); -#else QMessageBox::warning(this, tr("Save to file error", "Message box window title"), tr("Unable to save to file %1").arg(name) + ":\n" + f.errorString()); -#endif } /*! Restores the QGLViewer state from the stateFileName() file using initFromDOMElement(). @@ -3724,11 +3478,7 @@ bool QGLViewer::restoreStateFromFile() // Read the DOM tree form file QFile f(name); -#if QT_VERSION >= 0x040000 - if (f.open(QIODevice::ReadOnly) == true) -#else - if (f.open(IO_ReadOnly) == true) -#endif + if (f.open(QIODevice::ReadOnly)) { QDomDocument doc; doc.setContent(&f); @@ -3738,11 +3488,7 @@ bool QGLViewer::restoreStateFromFile() } else { -#if QT_VERSION < 0x030200 - QMessageBox::warning(this, tr("Open file error", "Message box window title"), tr("Unable to open file %1").arg(name)); -#else QMessageBox::warning(this, tr("Open file error", "Message box window title"), tr("Unable to open file %1").arg(name) + ":\n" + f.errorString()); -#endif return false; } @@ -3787,23 +3533,23 @@ QDomElement QGLViewer::domElement(const QString& name, QDomDocument& document) c de.setAttribute("version", QGLViewerVersionString()); QDomElement stateNode = document.createElement("State"); - // stateNode.setAttribute("mouseTracking", (hasMouseTracking()?"true":"false")); + // hasMouseTracking() is not saved stateNode.appendChild(DomUtils::QColorDomElement(foregroundColor(), "foregroundColor", document)); stateNode.appendChild(DomUtils::QColorDomElement(backgroundColor(), "backgroundColor", document)); - stateNode.setAttribute("stereo", (displaysInStereo()?"true":"false")); - stateNode.setAttribute("cameraMode", (cameraIsInRevolveMode()?"revolve":"fly")); + DomUtils::setBoolAttribute(stateNode, "stereo", displaysInStereo()); + // Revolve or fly camera mode is not saved de.appendChild(stateNode); QDomElement displayNode = document.createElement("Display"); - displayNode.setAttribute("axisIsDrawn", (axisIsDrawn()?"true":"false")); - displayNode.setAttribute("gridIsDrawn", (gridIsDrawn()?"true":"false")); - displayNode.setAttribute("FPSIsDisplayed", (FPSIsDisplayed()?"true":"false")); - displayNode.setAttribute("cameraIsEdited", (cameraIsEdited()?"true":"false")); - // displayNode.setAttribute("textIsEnabled", (textIsEnabled()?"true":"false")); + DomUtils::setBoolAttribute(displayNode, "axisIsDrawn", axisIsDrawn()); + DomUtils::setBoolAttribute(displayNode, "gridIsDrawn", gridIsDrawn()); + DomUtils::setBoolAttribute(displayNode, "FPSIsDisplayed", FPSIsDisplayed()); + DomUtils::setBoolAttribute(displayNode, "cameraIsEdited", cameraIsEdited()); + // textIsEnabled() is not saved de.appendChild(displayNode); QDomElement geometryNode = document.createElement("Geometry"); - geometryNode.setAttribute("fullScreen", (isFullScreen()?"true":"false")); + DomUtils::setBoolAttribute(geometryNode, "fullScreen", isFullScreen()); if (isFullScreen()) { geometryNode.setAttribute("prevPosX", QString::number(prevPos_.x())); @@ -3873,11 +3619,7 @@ void QGLViewer::initFromDOMElement(const QDomElement& element) // if (version != QGLViewerVersionString()) if (version[0] != '2') // Patches for previous versions should go here when the state file syntax is modified. -#if QT_VERSION >= 0x040000 qWarning("State file created using QGLViewer version %s may not be correctly read.", version.toLatin1().constData()); -#else - qWarning("State file created using QGLViewer version %s may not be correctly read.", version.latin1()); -#endif QDomElement child=element.firstChild().toElement(); bool tmpCameraIsEdited = cameraIsEdited(); @@ -3888,8 +3630,8 @@ void QGLViewer::initFromDOMElement(const QDomElement& element) // #CONNECTION# default values from defaultConstructor() // setMouseTracking(DomUtils::boolFromDom(child, "mouseTracking", false)); setStereoDisplay(DomUtils::boolFromDom(child, "stereo", false)); - if ((child.attribute("cameraMode", "revolve") == "fly") && (cameraIsInRevolveMode())) - toggleCameraMode(); + //if ((child.attribute("cameraMode", "revolve") == "fly") && (cameraIsInRevolveMode())) + // toggleCameraMode(); QDomElement ch=child.firstChild().toElement(); while (!ch.isNull()) @@ -4055,8 +3797,8 @@ void QGLViewer::copyBufferToTexture(GLint internalFormat, GLenum format) { bufferTextureWidth_ = w; bufferTextureHeight_ = h; - bufferTextureMaxU_ = width() / float(bufferTextureWidth_); - bufferTextureMaxV_ = height() / float(bufferTextureHeight_); + bufferTextureMaxU_ = width() / qreal(bufferTextureWidth_); + bufferTextureMaxV_ = height() / qreal(bufferTextureHeight_); init = true; } @@ -4082,7 +3824,7 @@ void QGLViewer::copyBufferToTexture(GLint internalFormat, GLenum format) if (init) { if (format == GL_NONE) - format = internalFormat; + format = GLenum(internalFormat); glTexImage2D(GL_TEXTURE_2D, 0, internalFormat, bufferTextureWidth_, bufferTextureHeight_, 0, format, GL_UNSIGNED_BYTE, NULL); } diff --git a/octovis/src/extern/QGLViewer/qglviewer.h b/octovis/src/extern/QGLViewer/qglviewer.h index 0e715610..14a08192 100644 --- a/octovis/src/extern/QGLViewer/qglviewer.h +++ b/octovis/src/extern/QGLViewer/qglviewer.h @@ -1,8 +1,8 @@ /**************************************************************************** - Copyright (C) 2002-2013 Gilles Debunne. All rights reserved. + Copyright (C) 2002-2014 Gilles Debunne. All rights reserved. - This file is part of the QGLViewer library version 2.4.0. + This file is part of the QGLViewer library version 2.6.3. http://www.libqglviewer.com - contact@libqglviewer.com @@ -25,26 +25,18 @@ #include "camera.h" -#if QT_VERSION >= 0x040000 -# include -# include -#else -# include -# include -#endif +#include +#include +#include class QTabWidget; namespace qglviewer { - class MouseGrabber; +class MouseGrabber; +class ManipulatedFrame; +class ManipulatedCameraFrame; } -#if QT_VERSION < 0x040000 -# define Qt::KeyboardModifiers Qt::ButtonState -# define Qt::MouseButtons Qt::ButtonState -# define Qt::WindowFlags Qt::WFlags -#endif - /*! \brief A versatile 3D OpenGL viewer based on QGLWidget. \class QGLViewer qglviewer.h QGLViewer/qglviewer.h @@ -74,31 +66,24 @@ class QGLVIEWER_EXPORT QGLViewer : public QGLWidget public: // Complete implementation is provided so that the constructor is defined with QT3_SUPPORT when .h is included. // (Would not be available otherwise since lib is compiled without QT3_SUPPORT). -#if QT_VERSION < 0x040000 || defined QT3_SUPPORT - explicit QGLViewer(QWidget* parent=NULL, const char* name=0, const QGLWidget* shareWidget=0, Qt::WindowFlags flags=0) +#ifdef QT3_SUPPORT + explicit QGLViewer(QWidget* parent=NULL, const char* name=0, const QGLWidget* shareWidget=0, Qt::WindowFlags flags=0) : QGLWidget(parent, name, shareWidget, flags) { defaultConstructor(); } - explicit QGLViewer(const QGLFormat& format, QWidget* parent=0, const char* name=0, const QGLWidget* shareWidget=0,Qt::WindowFlags flags=0) + explicit QGLViewer(const QGLFormat& format, QWidget* parent=0, const char* name=0, const QGLWidget* shareWidget=0,Qt::WindowFlags flags=0) : QGLWidget(format, parent, name, shareWidget, flags) { defaultConstructor(); } - QGLViewer(QGLContext* context, QWidget* parent, const char* name=0, const QGLWidget* shareWidget=0, Qt::WindowFlags flags=0) -# if QT_VERSION >= 0x030200 + QGLViewer(QGLContext* context, QWidget* parent, const char* name=0, const QGLWidget* shareWidget=0, Qt::WindowFlags flags=0) : QGLWidget(context, parent, name, shareWidget, flags) { -# else - // MOC_SKIP_BEGIN - : QGLWidget(parent, name, shareWidget, flags) { - Q_UNUSED(context); - // MOC_SKIP_END -# endif - defaultConstructor(); } + defaultConstructor(); } #else - explicit QGLViewer(QWidget* parent=0, const QGLWidget* shareWidget=0, Qt::WindowFlags flags=0); - explicit QGLViewer(QGLContext *context, QWidget* parent=0, const QGLWidget* shareWidget=0, Qt::WindowFlags flags=0); - explicit QGLViewer(const QGLFormat& format, QWidget* parent=0, const QGLWidget* shareWidget=0, Qt::WindowFlags flags=0); + explicit QGLViewer(QWidget* parent=0, const QGLWidget* shareWidget=0, Qt::WindowFlags flags=0); + explicit QGLViewer(QGLContext *context, QWidget* parent=0, const QGLWidget* shareWidget=0, Qt::WindowFlags flags=0); + explicit QGLViewer(const QGLFormat& format, QWidget* parent=0, const QGLWidget* shareWidget=0, Qt::WindowFlags flags=0); #endif virtual ~QGLViewer(); @@ -109,23 +94,23 @@ class QGLVIEWER_EXPORT QGLViewer : public QGLWidget /*! Returns \c true if the world axis is drawn by the viewer. Set by setAxisIsDrawn() or toggleAxisIsDrawn(). Default value is \c false. */ - bool axisIsDrawn() const { return axisIsDrawn_; }; + bool axisIsDrawn() const { return axisIsDrawn_; } /*! Returns \c true if a XY grid is drawn by the viewer. Set by setGridIsDrawn() or toggleGridIsDrawn(). Default value is \c false. */ - bool gridIsDrawn() const { return gridIsDrawn_; }; + bool gridIsDrawn() const { return gridIsDrawn_; } /*! Returns \c true if the viewer displays the current frame rate (Frames Per Second). Use QApplication::setFont() to define the display font (see drawText()). Set by setFPSIsDisplayed() or toggleFPSIsDisplayed(). Use currentFPS() to get the current FPS. Default value is \c false. */ - bool FPSIsDisplayed() const { return FPSIsDisplayed_; }; + bool FPSIsDisplayed() const { return FPSIsDisplayed_; } /*! Returns \c true if text display (see drawText()) is enabled. Set by setTextIsEnabled() or toggleTextIsEnabled(). This feature conveniently removes all the possibly displayed text, cleaning display. Default value is \c true. */ - bool textIsEnabled() const { return textIsEnabled_; }; + bool textIsEnabled() const { return textIsEnabled_; } /*! Returns \c true if the camera() is being edited in the viewer. @@ -138,32 +123,32 @@ class QGLVIEWER_EXPORT QGLViewer : public QGLWidget bool cameraIsEdited() const { return cameraIsEdited_; } - public Q_SLOTS: - /*! Sets the state of axisIsDrawn(). Emits the axisIsDrawnChanged() signal. See also toggleAxisIsDrawn(). */ - void setAxisIsDrawn(bool draw=true) { axisIsDrawn_ = draw; Q_EMIT axisIsDrawnChanged(draw); if (updateGLOK_) updateGL(); }; - /*! Sets the state of gridIsDrawn(). Emits the gridIsDrawnChanged() signal. See also toggleGridIsDrawn(). */ - void setGridIsDrawn(bool draw=true) { gridIsDrawn_ = draw; Q_EMIT gridIsDrawnChanged(draw); if (updateGLOK_) updateGL(); }; - /*! Sets the state of FPSIsDisplayed(). Emits the FPSIsDisplayedChanged() signal. See also toggleFPSIsDisplayed(). */ - void setFPSIsDisplayed(bool display=true) { FPSIsDisplayed_ = display; Q_EMIT FPSIsDisplayedChanged(display); if (updateGLOK_) updateGL(); }; - /*! Sets the state of textIsEnabled(). Emits the textIsEnabledChanged() signal. See also toggleTextIsEnabled(). */ - void setTextIsEnabled(bool enable=true) { textIsEnabled_ = enable; Q_EMIT textIsEnabledChanged(enable); if (updateGLOK_) updateGL(); }; - void setCameraIsEdited(bool edit=true); - - /*! Toggles the state of axisIsDrawn(). See also setAxisIsDrawn(). */ - void toggleAxisIsDrawn() { setAxisIsDrawn(!axisIsDrawn()); }; - /*! Toggles the state of gridIsDrawn(). See also setGridIsDrawn(). */ - void toggleGridIsDrawn() { setGridIsDrawn(!gridIsDrawn()); }; - /*! Toggles the state of FPSIsDisplayed(). See also setFPSIsDisplayed(). */ - void toggleFPSIsDisplayed() { setFPSIsDisplayed(!FPSIsDisplayed()); }; - /*! Toggles the state of textIsEnabled(). See also setTextIsEnabled(). */ - void toggleTextIsEnabled() { setTextIsEnabled(!textIsEnabled()); }; - /*! Toggles the state of cameraIsEdited(). See also setCameraIsEdited(). */ - void toggleCameraIsEdited() { setCameraIsEdited(!cameraIsEdited()); }; - //@} - - - /*! @name Viewer's colors */ - //@{ +public Q_SLOTS: + /*! Sets the state of axisIsDrawn(). Emits the axisIsDrawnChanged() signal. See also toggleAxisIsDrawn(). */ + void setAxisIsDrawn(bool draw=true) { axisIsDrawn_ = draw; Q_EMIT axisIsDrawnChanged(draw); update(); } + /*! Sets the state of gridIsDrawn(). Emits the gridIsDrawnChanged() signal. See also toggleGridIsDrawn(). */ + void setGridIsDrawn(bool draw=true) { gridIsDrawn_ = draw; Q_EMIT gridIsDrawnChanged(draw); update(); } + /*! Sets the state of FPSIsDisplayed(). Emits the FPSIsDisplayedChanged() signal. See also toggleFPSIsDisplayed(). */ + void setFPSIsDisplayed(bool display=true) { FPSIsDisplayed_ = display; Q_EMIT FPSIsDisplayedChanged(display); update(); } + /*! Sets the state of textIsEnabled(). Emits the textIsEnabledChanged() signal. See also toggleTextIsEnabled(). */ + void setTextIsEnabled(bool enable=true) { textIsEnabled_ = enable; Q_EMIT textIsEnabledChanged(enable); update(); } + void setCameraIsEdited(bool edit=true); + + /*! Toggles the state of axisIsDrawn(). See also setAxisIsDrawn(). */ + void toggleAxisIsDrawn() { setAxisIsDrawn(!axisIsDrawn()); } + /*! Toggles the state of gridIsDrawn(). See also setGridIsDrawn(). */ + void toggleGridIsDrawn() { setGridIsDrawn(!gridIsDrawn()); } + /*! Toggles the state of FPSIsDisplayed(). See also setFPSIsDisplayed(). */ + void toggleFPSIsDisplayed() { setFPSIsDisplayed(!FPSIsDisplayed()); } + /*! Toggles the state of textIsEnabled(). See also setTextIsEnabled(). */ + void toggleTextIsEnabled() { setTextIsEnabled(!textIsEnabled()); } + /*! Toggles the state of cameraIsEdited(). See also setCameraIsEdited(). */ + void toggleCameraIsEdited() { setCameraIsEdited(!cameraIsEdited()); } + //@} + + + /*! @name Viewer's colors */ + //@{ public: /*! Returns the background color of the viewer. @@ -173,39 +158,39 @@ class QGLVIEWER_EXPORT QGLViewer : public QGLWidget Use setBackgroundColor() to define and activate a background color. - \attention Each QColor component is an integer ranging from 0 to 255. This differs from the float + \attention Each QColor component is an integer ranging from 0 to 255. This differs from the qreal values used by \c glClearColor() which are in the 0.0-1.0 range. Default value is (51, 51, 51) (dark gray). You may have to change foregroundColor() accordingly. \attention This method does not return the current OpenGL clear color as \c glGet() does. Instead, it returns the QGLViewer internal variable. If you directly use \c glClearColor() or \c qglClearColor() instead of setBackgroundColor(), the two results will differ. */ - QColor backgroundColor() const { return backgroundColor_; }; + QColor backgroundColor() const { return backgroundColor_; } /*! Returns the foreground color used by the viewer. This color is used when FPSIsDisplayed(), gridIsDrawn(), to display the camera paths when the cameraIsEdited(). - \attention Each QColor component is an integer in the range 0-255. This differs from the float + \attention Each QColor component is an integer in the range 0-255. This differs from the qreal values used by \c glColor3f() which are in the range 0-1. Default value is (180, 180, 180) (light gray). Use \c qglColor(foregroundColor()) to set the current OpenGL color to the foregroundColor(). See also backgroundColor(). */ - QColor foregroundColor() const { return foregroundColor_; }; - public Q_SLOTS: - /*! Sets the backgroundColor() of the viewer and calls \c qglClearColor(). See also + QColor foregroundColor() const { return foregroundColor_; } +public Q_SLOTS: + /*! Sets the backgroundColor() of the viewer and calls \c qglClearColor(). See also setForegroundColor(). */ - void setBackgroundColor(const QColor& color) { backgroundColor_=color; qglClearColor(color); }; - /*! Sets the foregroundColor() of the viewer, used to draw visual hints. See also setBackgroundColor(). */ - void setForegroundColor(const QColor& color) { foregroundColor_ = color; }; - //@} + void setBackgroundColor(const QColor& color) { backgroundColor_=color; qglClearColor(color); } + /*! Sets the foregroundColor() of the viewer, used to draw visual hints. See also setBackgroundColor(). */ + void setForegroundColor(const QColor& color) { foregroundColor_ = color; } + //@} - /*! @name Scene dimensions */ - //@{ + /*! @name Scene dimensions */ + //@{ public: /*! Returns the scene radius. @@ -218,7 +203,7 @@ class QGLVIEWER_EXPORT QGLViewer : public QGLWidget Default value is 1.0. This method is equivalent to camera()->sceneRadius(). See setSceneRadius(). */ - float sceneRadius() const { return camera()->sceneRadius(); } + qreal sceneRadius() const { return camera()->sceneRadius(); } /*! Returns the scene center, defined in world coordinates. See sceneRadius() for details. @@ -226,43 +211,43 @@ class QGLVIEWER_EXPORT QGLViewer : public QGLWidget Default value is (0,0,0). Simply a wrapper for camera()->sceneCenter(). Set using setSceneCenter(). - Do not mismatch this value (that only depends on the scene) with the qglviewer::Camera::revolveAroundPoint(). */ + Do not mismatch this value (that only depends on the scene) with the qglviewer::Camera::pivotPoint(). */ qglviewer::Vec sceneCenter() const { return camera()->sceneCenter(); } - public Q_SLOTS: - /*! Sets the sceneRadius(). +public Q_SLOTS: + /*! Sets the sceneRadius(). The camera() qglviewer::Camera::flySpeed() is set to 1% of this value by this method. Simple wrapper around camera()->setSceneRadius(). */ - virtual void setSceneRadius(float radius) { camera()->setSceneRadius(radius); } + virtual void setSceneRadius(qreal radius) { camera()->setSceneRadius(radius); } - /*! Sets the sceneCenter(), defined in world coordinates. + /*! Sets the sceneCenter(), defined in world coordinates. - \attention The qglviewer::Camera::revolveAroundPoint() is set to the sceneCenter() value by this + \attention The qglviewer::Camera::pivotPoint() is set to the sceneCenter() value by this method. */ - virtual void setSceneCenter(const qglviewer::Vec& center) { camera()->setSceneCenter(center); } + virtual void setSceneCenter(const qglviewer::Vec& center) { camera()->setSceneCenter(center); } - /*! Convenient way to call setSceneCenter() and setSceneRadius() from a (world axis aligned) bounding box of the scene. + /*! Convenient way to call setSceneCenter() and setSceneRadius() from a (world axis aligned) bounding box of the scene. This is equivalent to: \code setSceneCenter((min+max) / 2.0); setSceneRadius((max-min).norm() / 2.0); \endcode */ - void setSceneBoundingBox(const qglviewer::Vec& min, const qglviewer::Vec& max) { camera()->setSceneBoundingBox(min,max); } + void setSceneBoundingBox(const qglviewer::Vec& min, const qglviewer::Vec& max) { camera()->setSceneBoundingBox(min,max); } - /*! Moves the camera so that the entire scene is visible. + /*! Moves the camera so that the entire scene is visible. Simple wrapper around qglviewer::Camera::showEntireScene(). */ - void showEntireScene() { camera()->showEntireScene(); if (updateGLOK_) updateGL(); } - //@} + void showEntireScene() { camera()->showEntireScene(); update(); } + //@} - /*! @name Associated objects */ - //@{ + /*! @name Associated objects */ + //@{ public: /*! Returns the associated qglviewer::Camera, never \c NULL. */ - qglviewer::Camera* camera() const { return camera_; }; + qglviewer::Camera* camera() const { return camera_; } /*! Returns the viewer's qglviewer::ManipulatedFrame. @@ -274,16 +259,16 @@ class QGLVIEWER_EXPORT QGLViewer : public QGLWidget implementation. Default value is \c NULL, meaning that no qglviewer::ManipulatedFrame is set. */ - qglviewer::ManipulatedFrame* manipulatedFrame() const { return manipulatedFrame_; }; + qglviewer::ManipulatedFrame* manipulatedFrame() const { return manipulatedFrame_; } - public Q_SLOTS: - void setCamera(qglviewer::Camera* const camera); - void setManipulatedFrame(qglviewer::ManipulatedFrame* frame); - //@} +public Q_SLOTS: + void setCamera(qglviewer::Camera* const camera); + void setManipulatedFrame(qglviewer::ManipulatedFrame* frame); + //@} - /*! @name Mouse grabbers */ - //@{ + /*! @name Mouse grabbers */ + //@{ public: /*! Returns the current qglviewer::MouseGrabber, or \c NULL if no qglviewer::MouseGrabber currently grabs mouse events. @@ -301,7 +286,7 @@ class QGLVIEWER_EXPORT QGLViewer : public QGLWidget \endcode Note that mouse tracking is disabled by default. Use QWidget::hasMouseTracking() to retrieve current state. */ - qglviewer::MouseGrabber* mouseGrabber() const { return mouseGrabber_; }; + qglviewer::MouseGrabber* mouseGrabber() const { return mouseGrabber_; } void setMouseGrabberIsEnabled(const qglviewer::MouseGrabber* const mouseGrabber, bool enabled=true); /*! Returns \c true if \p mouseGrabber is enabled. @@ -313,17 +298,17 @@ class QGLVIEWER_EXPORT QGLViewer : public QGLWidget You can also use qglviewer::MouseGrabber::removeFromMouseGrabberPool() to completely disable a MouseGrabber in all the QGLViewers. */ - bool mouseGrabberIsEnabled(const qglviewer::MouseGrabber* const mouseGrabber) { return !disabledMouseGrabbers_.contains(reinterpret_cast(mouseGrabber)); }; - public Q_SLOTS: - void setMouseGrabber(qglviewer::MouseGrabber* mouseGrabber); - //@} + bool mouseGrabberIsEnabled(const qglviewer::MouseGrabber* const mouseGrabber) { return !disabledMouseGrabbers_.contains(reinterpret_cast(mouseGrabber)); } +public Q_SLOTS: + void setMouseGrabber(qglviewer::MouseGrabber* mouseGrabber); + //@} - /*! @name State of the viewer */ - //@{ + /*! @name State of the viewer */ + //@{ public: /*! Returns the aspect ratio of the viewer's widget (width() / height()). */ - float aspectRatio() const { return static_cast(width())/static_cast(height()); }; + qreal aspectRatio() const { return width() / static_cast(height()); } /*! Returns the current averaged viewer frame rate. This value is computed and averaged over 20 successive frames. It only changes every 20 draw() @@ -334,14 +319,14 @@ class QGLVIEWER_EXPORT QGLViewer : public QGLWidget This value is meaningful only when draw() is regularly called, either using a \c QTimer, when animationIsStarted() or when the camera is manipulated with the mouse. */ - float currentFPS() { return f_p_s_; }; + qreal currentFPS() { return f_p_s_; } /*! Returns \c true if the viewer is in fullScreen mode. Default value is \c false. Set by setFullScreen() or toggleFullScreen(). Note that if the QGLViewer is embedded in an other QWidget, it returns \c true when the top level widget is in full screen mode. */ - bool isFullScreen() const { return fullScreen_; }; + bool isFullScreen() const { return fullScreen_; } /*! Returns \c true if the viewer displays in stereo. The QGLViewer object must be created with a stereo format to handle stereovision: @@ -365,42 +350,42 @@ class QGLVIEWER_EXPORT QGLViewer : public QGLWidget /*! Returns the recommended size for the QGLViewer. Default value is 600x400 pixels. */ virtual QSize sizeHint() const { return QSize(600, 400); } - public Q_SLOTS: - void setFullScreen(bool fullScreen=true); - void setStereoDisplay(bool stereo=true); - /*! Toggles the state of isFullScreen(). See also setFullScreen(). */ - void toggleFullScreen() { setFullScreen(!isFullScreen()); }; - /*! Toggles the state of displaysInStereo(). See setStereoDisplay(). */ - void toggleStereoDisplay() { setStereoDisplay(!stereo_); }; - void toggleCameraMode(); +public Q_SLOTS: + void setFullScreen(bool fullScreen=true); + void setStereoDisplay(bool stereo=true); + /*! Toggles the state of isFullScreen(). See also setFullScreen(). */ + void toggleFullScreen() { setFullScreen(!isFullScreen()); } + /*! Toggles the state of displaysInStereo(). See setStereoDisplay(). */ + void toggleStereoDisplay() { setStereoDisplay(!stereo_); } + void toggleCameraMode(); private: - bool cameraIsInRevolveMode() const; + bool cameraIsInRotateMode() const; //@} /*! @name Display methods */ //@{ public: - static void drawArrow(float length=1.0f, float radius=-1.0f, int nbSubdivisions=12); - static void drawArrow(const qglviewer::Vec& from, const qglviewer::Vec& to, float radius=-1.0f, int nbSubdivisions=12); - static void drawAxis(float length=1.0f); - static void drawGrid(float size=1.0f, int nbSubdivisions=10); + static void drawArrow(qreal length=1.0, qreal radius=-1.0, int nbSubdivisions=12); + static void drawArrow(const qglviewer::Vec& from, const qglviewer::Vec& to, qreal radius=-1.0, int nbSubdivisions=12); + static void drawAxis(qreal length=1.0); + static void drawGrid(qreal size=1.0, int nbSubdivisions=10); virtual void startScreenCoordinatesSystem(bool upward=false) const; virtual void stopScreenCoordinatesSystem() const; void drawText(int x, int y, const QString& text, const QFont& fnt=QFont()); void displayMessage(const QString& message, int delay=2000); - // void draw3DText(const qglviewer::Vec& pos, const qglviewer::Vec& normal, const QString& string, GLfloat height=0.1f); + // void draw3DText(const qglviewer::Vec& pos, const qglviewer::Vec& normal, const QString& string, GLfloat height=0.1); protected: - virtual void drawLight(GLenum light, float scale = 1.0f) const; + virtual void drawLight(GLenum light, qreal scale = 1.0) const; private: void displayFPS(); /*! Vectorial rendering callback method. */ - void drawVectorial() { paintGL(); }; + void drawVectorial() { paintGL(); } #ifndef DOXYGEN friend void drawVectorial(void* param); @@ -439,28 +424,25 @@ class QGLVIEWER_EXPORT QGLViewer : public QGLWidget You need to setMouseTracking() to \c true in order to use MouseGrabber (see mouseGrabber()). See details in the QWidget documentation. */ bool hasMouseTracking () const; - public Q_SLOTS: - /*! Resizes the widget to size \p width by \p height pixels. See also width() and height(). */ - virtual void resize(int width, int height); - /*! Sets the hasMouseTracking() value. */ - virtual void setMouseTracking(bool enable); +public Q_SLOTS: + /*! Resizes the widget to size \p width by \p height pixels. See also width() and height(). */ + virtual void resize(int width, int height); + /*! Sets the hasMouseTracking() value. */ + virtual void setMouseTracking(bool enable); protected: /*! Returns \c true when buffers are automatically swapped (default). See details in the QGLWidget documentation. */ bool autoBufferSwap() const; - protected Q_SLOTS: - /*! Sets the autoBufferSwap() value. */ - void setAutoBufferSwap(bool on); - //@} +protected Q_SLOTS: + /*! Sets the autoBufferSwap() value. */ + void setAutoBufferSwap(bool on); + //@} #endif - /*! @name Snapshots */ - //@{ + /*! @name Snapshots */ + //@{ public: -#if QT_VERSION < 0x030000 - virtual QImage grabFrameBuffer(bool withAlpha=false); -#endif /*! Returns the snapshot file name used by saveSnapshot(). This value is used in \p automatic mode (see saveSnapshot()). A dialog is otherwise popped-up to @@ -470,7 +452,7 @@ class QGLVIEWER_EXPORT QGLViewer : public QGLWidget If the file name is relative, the current working directory at the moment of the method call is used. Set using setSnapshotFileName(). */ - const QString& snapshotFileName() const { return snapshotFileName_; }; + const QString& snapshotFileName() const { return snapshotFileName_; } #ifndef DOXYGEN const QString& snapshotFilename() const; #endif @@ -502,13 +484,13 @@ class QGLVIEWER_EXPORT QGLViewer : public QGLWidget \attention No verification is performed on the provided format validity. The next call to saveSnapshot() may fail if the format string is not supported. */ - const QString& snapshotFormat() const { return snapshotFormat_; }; + const QString& snapshotFormat() const { return snapshotFormat_; } /*! Returns the value of the counter used to name snapshots in saveSnapshot() when \p automatic is \c true. Set using setSnapshotCounter(). Default value is 0, and it is incremented after each \p automatic snapshot. See saveSnapshot() for details. */ - int snapshotCounter() const { return snapshotCounter_; }; + int snapshotCounter() const { return snapshotCounter_; } /*! Defines the image quality of the snapshots produced with saveSnapshot(). Values must be in the range -1..100. Use 0 for lowest quality and 100 for highest quality (and @@ -517,36 +499,36 @@ class QGLVIEWER_EXPORT QGLViewer : public QGLWidget Set using setSnapshotQuality(). See also the QImage::save() documentation. \note This value has no impact on the images produced in vectorial format. */ - int snapshotQuality() { return snapshotQuality_; }; + int snapshotQuality() { return snapshotQuality_; } - // Qt 2.3 does not support double default value parameters in slots. + // Qt 2.3 does not support qreal default value parameters in slots. // Remove "Q_SLOTS" from the following line to compile with Qt 2.3 - public Q_SLOTS: +public Q_SLOTS: void saveSnapshot(bool automatic=true, bool overwrite=false); - public Q_SLOTS: +public Q_SLOTS: void saveSnapshot(const QString& fileName, bool overwrite=false); void setSnapshotFileName(const QString& name); /*! Sets the snapshotFormat(). */ - void setSnapshotFormat(const QString& format) { snapshotFormat_ = format; }; + void setSnapshotFormat(const QString& format) { snapshotFormat_ = format; } /*! Sets the snapshotCounter(). */ - void setSnapshotCounter(int counter) { snapshotCounter_ = counter; }; + void setSnapshotCounter(int counter) { snapshotCounter_ = counter; } /*! Sets the snapshotQuality(). */ - void setSnapshotQuality(int quality) { snapshotQuality_ = quality; }; + void setSnapshotQuality(int quality) { snapshotQuality_ = quality; } bool openSnapshotFormatDialog(); void snapshotToClipboard(); private: bool saveImageSnapshot(const QString& fileName); - + #ifndef DOXYGEN /* This class is used internally for screenshot that require tiling (image size size different from window size). Only in that case, is the private tileRegion_ pointer non null. It then contains the current tiled region, which is used by startScreenCoordinatesSystem to adapt the coordinate system. Not using it would result in a tiled drawing of the parts that use startScreenCoordinatesSystem. Also used by scaledFont for same purposes. */ - class TileRegion { public : double xMin, yMin, xMax, yMax, textScale; }; + class TileRegion { public : qreal xMin, yMin, xMax, yMax, textScale; }; #endif public: @@ -554,34 +536,30 @@ class QGLVIEWER_EXPORT QGLViewer : public QGLWidget From a user's point of view, this method simply returns \p font and can be used transparently. - However when internally rendering a screen snapshot using saveSnapshot(), it returns a scaled version - of the font, so that the size of the rendered text on the snapshot is identical to what is displayed on screen, + However when internally rendering a screen snapshot using saveSnapshot(), it returns a scaled version + of the font, so that the size of the rendered text on the snapshot is identical to what is displayed on screen, even if the snapshot uses image tiling to create an image of dimensions different from those of the current window. This scaled version will only be used when saveSnapshot() calls your draw() method to generate the snapshot. - All your calls to QGLWidget::renderText() function hence should use this method. + All your calls to QGLWidget::renderText() function hence should use this method. \code renderText(x, y, z, "My Text", scaledFont(QFont())); \endcode - will guarantee that this text will be properly displayed on arbitrary sized snapshots. + will guarantee that this text will be properly displayed on arbitrary sized snapshots. Note that this method is not needed if you use drawText() which already calls it internally. */ QFont scaledFont(const QFont& font) const { - if (tileRegion_ == NULL) - return font; - else { - QFont f(font); - if (f.pixelSize() == -1) -#if QT_VERSION >= 0x040000 - f.setPointSizeF(f.pointSizeF() * tileRegion_->textScale); -#else - f.setPointSizeFloat(f.pointSizeFloat() * tileRegion_->textScale); -#endif - else - f.setPixelSize(f.pixelSize() * tileRegion_->textScale); - return f; - } + if (tileRegion_ == NULL) + return font; + else { + QFont f(font); + if (f.pixelSize() == -1) + f.setPointSizeF(f.pointSizeF() * tileRegion_->textScale); + else + f.setPixelSize(int(f.pixelSize() * tileRegion_->textScale)); + return f; + } } //@} @@ -598,15 +576,15 @@ class QGLVIEWER_EXPORT QGLViewer : public QGLWidget Use (0,0) to (bufferTextureMaxU(), bufferTextureMaxV()) texture coordinates to map the entire texture on a quad. */ - float bufferTextureMaxU() const { return bufferTextureMaxU_; }; + qreal bufferTextureMaxU() const { return bufferTextureMaxU_; } /*! Same as bufferTextureMaxU(), but for the v texture coordinate. */ - float bufferTextureMaxV() const { return bufferTextureMaxV_; }; - public Q_SLOTS: - void copyBufferToTexture(GLint internalFormat, GLenum format=GL_NONE); - //@} + qreal bufferTextureMaxV() const { return bufferTextureMaxV_; } +public Q_SLOTS: + void copyBufferToTexture(GLint internalFormat, GLenum format=GL_NONE); + //@} - /*! @name Animation */ - //@{ + /*! @name Animation */ + //@{ public: /*! Return \c true when the animation loop is started. @@ -616,7 +594,7 @@ class QGLVIEWER_EXPORT QGLViewer : public QGLWidget Use startAnimation(), stopAnimation() or toggleAnimation() to change this value. See the animation example for illustration. */ - bool animationIsStarted() const { return animationStarted_; }; + bool animationIsStarted() const { return animationStarted_; } /*! The animation loop period, in milliseconds. When animationIsStarted(), this is delay waited after draw() to call animate() and draw() again. @@ -631,28 +609,28 @@ class QGLVIEWER_EXPORT QGLViewer : public QGLWidget \note This value is taken into account only the next time you call startAnimation(). If animationIsStarted(), you should stopAnimation() first. */ - int animationPeriod() const { return animationPeriod_; }; + int animationPeriod() const { return animationPeriod_; } - public Q_SLOTS: - /*! Sets the animationPeriod(), in milliseconds. */ - void setAnimationPeriod(int period) { animationPeriod_ = period; }; - virtual void startAnimation(); - virtual void stopAnimation(); - /*! Scene animation method. +public Q_SLOTS: + /*! Sets the animationPeriod(), in milliseconds. */ + void setAnimationPeriod(int period) { animationPeriod_ = period; } + virtual void startAnimation(); + virtual void stopAnimation(); + /*! Scene animation method. When animationIsStarted(), this method is in charge of the scene update before each draw(). Overload it to define how your scene evolves over time. The time should either be regularly incremented in this method (frame-rate independent animation) or computed from actual time (for instance using QTime::elapsed()) for real-time animations. - Note that KeyFrameInterpolator (which regularly updates a Frame) does not use this method - to animate a Frame, but rather rely on a QTimer signal-slot mechanism. + Note that KeyFrameInterpolator (which regularly updates a Frame) does not use this method + to animate a Frame, but rather rely on a QTimer signal-slot mechanism. See the animation example for an illustration. */ - virtual void animate() { Q_EMIT animateNeeded(); }; - /*! Calls startAnimation() or stopAnimation(), depending on animationIsStarted(). */ - void toggleAnimation() { if (animationIsStarted()) stopAnimation(); else startAnimation(); }; - //@} + virtual void animate() { Q_EMIT animateNeeded(); } + /*! Calls startAnimation() or stopAnimation(), depending on animationIsStarted(). */ + void toggleAnimation() { if (animationIsStarted()) stopAnimation(); else startAnimation(); } + //@} public: Q_SIGNALS: @@ -732,7 +710,7 @@ class QGLVIEWER_EXPORT QGLViewer : public QGLWidget \endcode See also mouseString() and keyboardString(). */ - virtual QString helpString() const { return tr("No help available."); }; + virtual QString helpString() const { return tr("No help available."); } virtual QString mouseString() const; virtual QString keyboardString() const; @@ -744,9 +722,9 @@ class QGLVIEWER_EXPORT QGLViewer : public QGLWidget virtual QString shortcutBindingsString () const { return keyboardString(); } #endif - public Q_SLOTS: - virtual void help(); - virtual void aboutQGLViewer(); +public Q_SLOTS: + virtual void help(); + virtual void aboutQGLViewer(); protected: /*! Returns a pointer to the help widget. @@ -781,7 +759,7 @@ class QGLVIEWER_EXPORT QGLViewer : public QGLWidget \note All the OpenGL specific initializations must be done in this method: the OpenGL context is not yet available in your viewer constructor. */ - virtual void init() { Q_EMIT viewerInitialized(); }; + virtual void init() { Q_EMIT viewerInitialized(); } virtual void paintGL(); virtual void preDraw(); @@ -802,7 +780,7 @@ class QGLVIEWER_EXPORT QGLViewer : public QGLWidget camera()->loadProjectionMatrix() at the end of draw() if you need to change the projection matrix (unlikely). On the other hand, the \c GL_MODELVIEW matrix can be modified and left in a arbitrary state. */ - virtual void draw() {}; + virtual void draw() {} virtual void fastDraw(); virtual void postDraw(); //@} @@ -816,6 +794,7 @@ class QGLVIEWER_EXPORT QGLViewer : public QGLWidget virtual void mouseDoubleClickEvent(QMouseEvent *); virtual void wheelEvent(QWheelEvent *); virtual void keyPressEvent(QKeyEvent *); + virtual void keyReleaseEvent(QKeyEvent *); virtual void timerEvent(QTimerEvent *); virtual void closeEvent(QCloseEvent *); //@} @@ -830,7 +809,7 @@ class QGLVIEWER_EXPORT QGLViewer : public QGLWidget was selected. Return value is -1 before the first call to select(). This value is modified using setSelectedName(). */ - int selectedName() const { return selectedObjectId_; }; + int selectedName() const { return selectedObjectId_; } /*! Returns the selectBuffer() size. See the select() documentation for details. Use setSelectBufferSize() to change this value. @@ -838,7 +817,7 @@ class QGLVIEWER_EXPORT QGLViewer : public QGLWidget Default value is 4000 (i.e. 1000 objects in selection region, since each object pushes 4 values). This size should be over estimated to prevent a buffer overflow when many objects are drawn under the mouse cursor. */ - int selectBufferSize() const { return selectBufferSize_; }; + int selectBufferSize() const { return selectBufferSize_; } /*! Returns the width (in pixels) of a selection frustum, centered on the mouse cursor, that is used to select objects. @@ -853,31 +832,31 @@ class QGLVIEWER_EXPORT QGLViewer : public QGLWidget more precise selection but the user has to be careful for small feature selection. See the multiSelect example for an illustration. */ - int selectRegionWidth() const { return selectRegionWidth_; }; + int selectRegionWidth() const { return selectRegionWidth_; } /*! See the selectRegionWidth() documentation. Default value is 3 pixels. */ - int selectRegionHeight() const { return selectRegionHeight_; }; + int selectRegionHeight() const { return selectRegionHeight_; } /*! Returns a pointer to an array of \c GLuint. This buffer is used by the \c GL_SELECT mode in select() to perform object selection. The buffer size can be modified using setSelectBufferSize(). If you overload endSelection(), you will analyze the content of this buffer. See the \c glSelectBuffer() man page for details. */ - GLuint* selectBuffer() { return selectBuffer_; }; + GLuint* selectBuffer() { return selectBuffer_; } - public Q_SLOTS: - virtual void select(const QMouseEvent* event); - virtual void select(const QPoint& point); +public Q_SLOTS: + virtual void select(const QMouseEvent* event); + virtual void select(const QPoint& point); - void setSelectBufferSize(int size); - /*! Sets the selectRegionWidth(). */ - void setSelectRegionWidth(int width) { selectRegionWidth_ = width; }; - /*! Sets the selectRegionHeight(). */ - void setSelectRegionHeight(int height) { selectRegionHeight_ = height; }; - /*! Set the selectedName() value. + void setSelectBufferSize(int size); + /*! Sets the selectRegionWidth(). */ + void setSelectRegionWidth(int width) { selectRegionWidth_ = width; } + /*! Sets the selectRegionHeight(). */ + void setSelectRegionHeight(int height) { selectRegionHeight_ = height; } + /*! Set the selectedName() value. Used in endSelection() during a selection. You should only call this method if you overload the endSelection() method. */ - void setSelectedName(int id) { selectedObjectId_=id; }; + void setSelectedName(int id) { selectedObjectId_=id; } protected: virtual void beginSelection(const QPoint& point); @@ -890,9 +869,9 @@ class QGLVIEWER_EXPORT QGLViewer : public QGLWidget \code void Viewer::drawWithNames() { for (int i=0; idraw(); - glPopName(); + glPushName(i); + object(i)->draw(); + glPopName(); } } \endcode @@ -903,7 +882,7 @@ void Viewer::drawWithNames() { \attention If your selected objects are points, do not use \c glBegin(GL_POINTS); and \c glVertex3fv() in the above \c draw() method (not compatible with raster mode): use \c glRasterPos3fv() instead. */ - virtual void drawWithNames() {}; + virtual void drawWithNames() {} virtual void endSelection(const QPoint& point); /*! This method is called at the end of the select() procedure. It should finalize the selection process and update the data structure/interface/computation/display... according to the newly @@ -912,120 +891,140 @@ void Viewer::drawWithNames() { The default implementation is empty. Overload this method if needed, and use selectedName() to retrieve the selected entity name (returns -1 if no object was selected). See the select example for an illustration. */ - virtual void postSelection(const QPoint& point) { Q_UNUSED(point); }; + virtual void postSelection(const QPoint& point) { Q_UNUSED(point); } //@} /*! @name Keyboard customization */ //@{ -protected: +public: /*! Defines the different actions that can be associated with a keyboard shortcut using setShortcut(). See the keyboard page for details. */ enum KeyboardAction { DRAW_AXIS, DRAW_GRID, DISPLAY_FPS, ENABLE_TEXT, EXIT_VIEWER, - SAVE_SCREENSHOT, CAMERA_MODE, FULL_SCREEN, STEREO, ANIMATION, HELP, EDIT_CAMERA, - MOVE_CAMERA_LEFT, MOVE_CAMERA_RIGHT, MOVE_CAMERA_UP, MOVE_CAMERA_DOWN, - INCREASE_FLYSPEED, DECREASE_FLYSPEED, SNAPSHOT_TO_CLIPBOARD }; -public: - unsigned int shortcut(KeyboardAction action) const; + SAVE_SCREENSHOT, CAMERA_MODE, FULL_SCREEN, STEREO, ANIMATION, HELP, EDIT_CAMERA, + MOVE_CAMERA_LEFT, MOVE_CAMERA_RIGHT, MOVE_CAMERA_UP, MOVE_CAMERA_DOWN, + INCREASE_FLYSPEED, DECREASE_FLYSPEED, SNAPSHOT_TO_CLIPBOARD }; + + unsigned int shortcut(KeyboardAction action) const; #ifndef DOXYGEN // QGLViewer 1.x - int keyboardAccelerator(KeyboardAction action) const; - Qt::Key keyFrameKey(int index) const; - Qt::KeyboardModifiers playKeyFramePathStateKey() const; + unsigned int keyboardAccelerator(KeyboardAction action) const; + Qt::Key keyFrameKey(unsigned int index) const; + Qt::KeyboardModifiers playKeyFramePathStateKey() const; // QGLViewer 2.0 without Qt4 support - Qt::KeyboardModifiers addKeyFrameStateKey() const; - Qt::KeyboardModifiers playPathStateKey() const; + Qt::KeyboardModifiers addKeyFrameStateKey() const; + Qt::KeyboardModifiers playPathStateKey() const; #endif - Qt::Key pathKey(int index) const; - Qt::KeyboardModifiers addKeyFrameKeyboardModifiers() const; - Qt::KeyboardModifiers playPathKeyboardModifiers() const; + Qt::Key pathKey(unsigned int index) const; + Qt::KeyboardModifiers addKeyFrameKeyboardModifiers() const; + Qt::KeyboardModifiers playPathKeyboardModifiers() const; - public Q_SLOTS: - void setShortcut(KeyboardAction action, unsigned int key); +public Q_SLOTS: + void setShortcut(KeyboardAction action, unsigned int key); #ifndef DOXYGEN - void setKeyboardAccelerator(KeyboardAction action, int key); + void setKeyboardAccelerator(KeyboardAction action, unsigned int key); #endif - void setKeyDescription(int key, QString description); + void setKeyDescription(unsigned int key, QString description); + void clearShortcuts(); - // Key Frames shortcut keys + // Key Frames shortcut keys #ifndef DOXYGEN - // QGLViewer 1.x compatibility methods - virtual void setKeyFrameKey(int index, int key); - virtual void setPlayKeyFramePathStateKey(int buttonState); - // QGLViewer 2.0 without Qt4 support - virtual void setPlayPathStateKey(int buttonState); - virtual void setAddKeyFrameStateKey(int buttonState); + // QGLViewer 1.x compatibility methods + virtual void setKeyFrameKey(unsigned int index, int key); + virtual void setPlayKeyFramePathStateKey(unsigned int buttonState); + // QGLViewer 2.0 without Qt4 support + virtual void setPlayPathStateKey(unsigned int buttonState); + virtual void setAddKeyFrameStateKey(unsigned int buttonState); #endif - virtual void setPathKey(int key, int index = 0); - virtual void setPlayPathKeyboardModifiers(Qt::KeyboardModifiers modifiers); - virtual void setAddKeyFrameKeyboardModifiers(Qt::KeyboardModifiers modifiers); - //@} + virtual void setPathKey(int key, unsigned int index = 0); + virtual void setPlayPathKeyboardModifiers(Qt::KeyboardModifiers modifiers); + virtual void setAddKeyFrameKeyboardModifiers(Qt::KeyboardModifiers modifiers); + //@} - /*! @name Mouse customization */ - //@{ -protected: +public: + /*! @name Mouse customization */ + //@{ /*! Defines the different mouse handlers: camera() or manipulatedFrame(). - Used by setMouseBinding(), setMouseBinding(int, ClickAction, bool, int) and setWheelBinding() to - define which handler receives the mouse events. */ + Used by setMouseBinding(), setMouseBinding(Qt::KeyboardModifiers modifiers, Qt::MouseButtons, ClickAction, bool, int) + and setWheelBinding() to define which handler receives the mouse events. */ enum MouseHandler { CAMERA, FRAME }; /*! Defines the possible actions that can be binded to a mouse click using - setMouseBinding(int,ClickAction,bool,int). + setMouseBinding(Qt::KeyboardModifiers, Qt::MouseButtons, ClickAction, bool, int). See the mouse page for details. */ enum ClickAction { NO_CLICK_ACTION, ZOOM_ON_PIXEL, ZOOM_TO_FIT, SELECT, RAP_FROM_PIXEL, RAP_IS_CENTER, - CENTER_FRAME, CENTER_SCENE, SHOW_ENTIRE_SCENE, ALIGN_FRAME, ALIGN_CAMERA }; + CENTER_FRAME, CENTER_SCENE, SHOW_ENTIRE_SCENE, ALIGN_FRAME, ALIGN_CAMERA }; -#ifndef DOXYGEN - // So that it can be used in ManipulatedFrame and ManipulatedCameraFrame. -public: -#endif - /*! Defines the possible actions that can be binded to a mouse motion (a click, followed by a + /*! Defines the possible actions that can be binded to a mouse action (a click, followed by a mouse displacement). These actions may be binded to the camera() or to the manipulatedFrame() (see QGLViewer::MouseHandler) using setMouseBinding(). */ enum MouseAction { NO_MOUSE_ACTION, - ROTATE, ZOOM, TRANSLATE, - MOVE_FORWARD, LOOK_AROUND, MOVE_BACKWARD, - SCREEN_ROTATE, ROLL, DRIVE, - SCREEN_TRANSLATE, ZOOM_ON_REGION }; + ROTATE, ZOOM, TRANSLATE, + MOVE_FORWARD, LOOK_AROUND, MOVE_BACKWARD, + SCREEN_ROTATE, ROLL, DRIVE, + SCREEN_TRANSLATE, ZOOM_ON_REGION }; -#ifdef DOXYGEN -public: +#ifndef DOXYGEN + MouseAction mouseAction(unsigned int state) const; + int mouseHandler(unsigned int state) const; + int mouseButtonState(MouseHandler handler, MouseAction action, bool withConstraint=true) const; + ClickAction clickAction(unsigned int state, bool doubleClick, Qt::MouseButtons buttonsBefore) const; + void getClickButtonState(ClickAction action, unsigned int & state, bool& doubleClick, Qt::MouseButtons& buttonsBefore) const; + unsigned int wheelButtonState(MouseHandler handler, MouseAction action, bool withConstraint=true) const; #endif - MouseAction mouseAction(int state) const; - int mouseHandler(int state) const; - int mouseButtonState(MouseHandler handler, MouseAction action, bool withConstraint=true) const; - ClickAction clickAction(int state, bool doubleClick, Qt::MouseButtons buttonsBefore) const; - void getClickButtonState(ClickAction action, int& state, bool& doubleClick, Qt::MouseButtons& buttonsBefore) const; + MouseAction mouseAction(Qt::Key key, Qt::KeyboardModifiers modifiers, Qt::MouseButton button) const; + int mouseHandler(Qt::Key key, Qt::KeyboardModifiers modifiers, Qt::MouseButton button) const; - MouseAction wheelAction(Qt::KeyboardModifiers modifiers) const; - int wheelHandler(Qt::KeyboardModifiers modifiers) const; - int wheelButtonState(MouseHandler handler, MouseAction action, bool withConstraint=true) const; + void getMouseActionBinding(MouseHandler handler, MouseAction action, bool withConstraint, + Qt::Key& key, Qt::KeyboardModifiers& modifiers, Qt::MouseButton& button) const; + + ClickAction clickAction(Qt::Key key, Qt::KeyboardModifiers modifiers, Qt::MouseButton button, + bool doubleClick=false, Qt::MouseButtons buttonsBefore=Qt::NoButton) const; + + void getClickActionBinding(ClickAction action, Qt::Key& key, Qt::KeyboardModifiers& modifiers, + Qt::MouseButton& button, bool& doubleClick, Qt::MouseButtons& buttonsBefore) const; + + MouseAction wheelAction(Qt::Key key, Qt::KeyboardModifiers modifiers) const; + int wheelHandler(Qt::Key key, Qt::KeyboardModifiers modifiers) const; + + void getWheelActionBinding(MouseHandler handler, MouseAction action, bool withConstraint, + Qt::Key& key, Qt::KeyboardModifiers& modifiers) const; public Q_SLOTS: - void setMouseBinding(int state, MouseHandler handler, MouseAction action, bool withConstraint=true); -#if QT_VERSION < 0x030000 - // Two slots cannot have the same name or two default parameters with Qt 2.3. -public: -#endif - void setMouseBinding(int state, ClickAction action, bool doubleClick=false, Qt::MouseButtons buttonsBefore=Qt::NoButton); -#if QT_VERSION < 0x030000 -public Q_SLOTS: +#ifndef DOXYGEN + void setMouseBinding(unsigned int state, MouseHandler handler, MouseAction action, bool withConstraint=true); + void setMouseBinding(unsigned int state, ClickAction action, bool doubleClick=false, Qt::MouseButtons buttonsBefore=Qt::NoButton); + void setMouseBindingDescription(unsigned int state, QString description, bool doubleClick=false, Qt::MouseButtons buttonsBefore=Qt::NoButton); #endif - void setMouseBindingDescription(int state, QString description, bool doubleClick=false, Qt::MouseButtons buttonsBefore=Qt::NoButton); - void setWheelBinding(Qt::KeyboardModifiers modifiers, MouseHandler handler, MouseAction action, bool withConstraint=true); - void setHandlerKeyboardModifiers(MouseHandler handler, Qt::KeyboardModifiers modifiers); + + void setMouseBinding(Qt::KeyboardModifiers modifiers, Qt::MouseButton buttons, MouseHandler handler, MouseAction action, bool withConstraint=true); + void setMouseBinding(Qt::KeyboardModifiers modifiers, Qt::MouseButton button, ClickAction action, bool doubleClick=false, Qt::MouseButtons buttonsBefore=Qt::NoButton); + void setWheelBinding(Qt::KeyboardModifiers modifiers, MouseHandler handler, MouseAction action, bool withConstraint=true); + void setMouseBindingDescription(Qt::KeyboardModifiers modifiers, Qt::MouseButton button, QString description, bool doubleClick=false, Qt::MouseButtons buttonsBefore=Qt::NoButton); + + void setMouseBinding(Qt::Key key, Qt::KeyboardModifiers modifiers, Qt::MouseButton buttons, MouseHandler handler, MouseAction action, bool withConstraint=true); + void setMouseBinding(Qt::Key key, Qt::KeyboardModifiers modifiers, Qt::MouseButton button, ClickAction action, bool doubleClick=false, Qt::MouseButtons buttonsBefore=Qt::NoButton); + void setWheelBinding(Qt::Key key, Qt::KeyboardModifiers modifiers, MouseHandler handler, MouseAction action, bool withConstraint=true); + void setMouseBindingDescription(Qt::Key key, Qt::KeyboardModifiers modifiers, Qt::MouseButton button, QString description, bool doubleClick=false, Qt::MouseButtons buttonsBefore=Qt::NoButton); + + void clearMouseBindings(); + #ifndef DOXYGEN - void setHandlerStateKey(MouseHandler handler, int buttonState); - void setMouseStateKey(MouseHandler handler, int buttonState); + MouseAction wheelAction(Qt::KeyboardModifiers modifiers) const; + int wheelHandler(Qt::KeyboardModifiers modifiers) const; + + void setHandlerKeyboardModifiers(MouseHandler handler, Qt::KeyboardModifiers modifiers); + void setHandlerStateKey(MouseHandler handler, unsigned int buttonState); + void setMouseStateKey(MouseHandler handler, unsigned int buttonState); #endif private: @@ -1040,12 +1039,12 @@ public Q_SLOTS: QString stateFileName() const; virtual QDomElement domElement(const QString& name, QDomDocument& document) const; - public Q_SLOTS: - virtual void initFromDOMElement(const QDomElement& element); - virtual void saveStateToFile(); // cannot be const because of QMessageBox - virtual bool restoreStateFromFile(); +public Q_SLOTS: + virtual void initFromDOMElement(const QDomElement& element); + virtual void saveStateToFile(); // cannot be const because of QMessageBox + virtual bool restoreStateFromFile(); - /*! Defines the stateFileName() used by saveStateToFile() and restoreStateFromFile(). + /*! Defines the stateFileName() used by saveStateToFile() and restoreStateFromFile(). The file name can have an optional prefix directory (no prefix meaning current directory). If the directory does not exist, it will be created by saveStateToFile(). @@ -1057,11 +1056,11 @@ public Q_SLOTS: // Files are stored in a dedicated directory under user's home directory. setStateFileName(QDir::homeDirPath + "/.config/myApp.xml"); \endcode */ - void setStateFileName(const QString& name) { stateFileName_ = name; }; + void setStateFileName(const QString& name) { stateFileName_ = name; } #ifndef DOXYGEN - void saveToFile(const QString& fileName=QString::null); - bool restoreFromFile(const QString& fileName=QString::null); + void saveToFile(const QString& fileName=QString::null); + bool restoreFromFile(const QString& fileName=QString::null); #endif private: @@ -1073,21 +1072,17 @@ public Q_SLOTS: //@{ public: /*! Returns a \c QList that contains pointers to all the created QGLViewers. - Note that this list may contain \c NULL pointers if the associated viewer has been deleted. + Note that this list may contain \c NULL pointers if the associated viewer has been deleted. Can be useful to apply a method or to connect a signal to all the viewers: - \code + \code foreach (QGLViewer* viewer, QGLViewer::QGLViewerPool()) - connect(myObject, SIGNAL(IHaveChangedSignal()), viewer, SLOT(updateGL())); + connect(myObject, SIGNAL(IHaveChangedSignal()), viewer, SLOT(update())); \endcode \attention With Qt version 3, this method returns a \c QPtrList instead. Use a \c QPtrListIterator to iterate on the list instead.*/ -#if QT_VERSION >= 0x040000 - static const QList& QGLViewerPool() { return QGLViewer::QGLViewerPool_; }; -#else - static const QPtrList& QGLViewerPool() { return QGLViewer::QGLViewerPool_; }; -#endif + static const QList& QGLViewerPool() { return QGLViewer::QGLViewerPool_; } /*! Returns the index of the QGLViewer \p viewer in the QGLViewerPool(). This index in unique and @@ -1095,13 +1090,9 @@ public Q_SLOTS: example). When a QGLViewer is deleted, the QGLViewers' indexes are preserved and NULL is set for that index. - When a QGLViewer is created, it is placed in the first available position in that list. - Returns -1 if the QGLViewer could not be found (which should not be possible). */ -#if QT_VERSION >= 0x040000 - static int QGLViewerIndex(const QGLViewer* const viewer) { return QGLViewer::QGLViewerPool_.indexOf(const_cast(viewer)); }; -#else - static int QGLViewerIndex(const QGLViewer* const viewer) { return QGLViewer::QGLViewerPool_.findRef(viewer); }; -#endif + When a QGLViewer is created, it is placed in the first available position in that list. + Returns -1 if the QGLViewer could not be found (which should not be possible). */ + static int QGLViewerIndex(const QGLViewer* const viewer) { return QGLViewer::QGLViewerPool_.indexOf(const_cast(viewer)); } //@} #ifndef DOXYGEN @@ -1111,15 +1102,15 @@ public Q_SLOTS: virtual void setVisualHintsMask(int mask, int delay = 2000); virtual void drawVisualHints(); - public Q_SLOTS: - virtual void resetVisualHints(); - //@} +public Q_SLOTS: + virtual void resetVisualHints(); + //@} #endif - private Q_SLOTS: - // Patch for a Qt bug with fullScreen on startup - void delayedFullScreen() { move(prevPos_); setFullScreen(); }; - void hideMessage(); +private Q_SLOTS: + // Patch for a Qt bug with fullScreen on startup + void delayedFullScreen() { move(prevPos_); setFullScreen(); } + void hideMessage(); private: // Copy constructor and operator= are declared private and undefined @@ -1135,8 +1126,8 @@ public Q_SLOTS: // C a m e r a qglviewer::Camera* camera_; bool cameraIsEdited_; - float previousCameraZClippingCoefficient_; - int previousPathId_; // Double key press recognition + qreal previousCameraZClippingCoefficient_; + unsigned int previousPathId_; // double key press recognition void connectAllCameraKFIInterpolatedSignals(bool connection=true); // C o l o r s @@ -1160,7 +1151,7 @@ public Q_SLOTS: QTime fpsTime_; unsigned int fpsCounter_; QString fpsString_; - float f_p_s_; + qreal f_p_s_; // M e s s a g e s QString message_; @@ -1190,16 +1181,16 @@ public Q_SLOTS: void setDefaultShortcuts(); QString cameraPathKeysString() const; QMap keyboardActionDescription_; - QMap keyboardBinding_; - QMap keyDescription_; + QMap keyboardBinding_; + QMap keyDescription_; // K e y F r a m e s s h o r t c u t s - QMap pathIndex_; - Qt::KeyboardModifiers addKeyFrameKeyboardModifiers_, playPathKeyboardModifiers_; + QMap pathIndex_; + Qt::KeyboardModifiers addKeyFrameKeyboardModifiers_, playPathKeyboardModifiers_; // B u f f e r T e x t u r e GLuint bufferTextureId_; - float bufferTextureMaxU_, bufferTextureMaxV_; + qreal bufferTextureMaxU_, bufferTextureMaxV_; int bufferTextureWidth_, bufferTextureHeight_; unsigned int previousBufferTextureFormat_; int previousBufferTextureInternalFormat_; @@ -1212,38 +1203,80 @@ public Q_SLOTS: bool withConstraint; }; - // C l i c k a c t i o n s - struct ClickActionPrivate { - Qt::KeyboardModifiers modifiers; - Qt::MouseButtons button; - bool doubleClick; - Qt::MouseButtons buttonsBefore; // only defined when doubleClick is true + // M o u s e b i n d i n g s + struct MouseBindingPrivate { + const Qt::KeyboardModifiers modifiers; + const Qt::MouseButton button; + const Qt::Key key; + + MouseBindingPrivate(Qt::KeyboardModifiers m, Qt::MouseButton b, Qt::Key k) + : modifiers(m), button(b), key(k) {} - // This sort order in used in mouseString() to displays sorted mouse bindings - bool operator<(const ClickActionPrivate& cap) const + // This sort order is used in mouseString() to display sorted mouse bindings + bool operator<(const MouseBindingPrivate& mbp) const { - if (buttonsBefore != cap.buttonsBefore) - return buttonsBefore < cap.buttonsBefore; - else - if (modifiers != cap.modifiers) - return modifiers < cap.modifiers; - else - if (button != cap.button) - return button < cap.button; - else - return !doubleClick && cap.doubleClick; + if (key != mbp.key) + return key < mbp.key; + if (modifiers != mbp.modifiers) + return modifiers < mbp.modifiers; + return button < mbp.button; + } + }; + + // W h e e l b i n d i n g s + struct WheelBindingPrivate { + const Qt::KeyboardModifiers modifiers; + const Qt::Key key; + + WheelBindingPrivate(Qt::KeyboardModifiers m, Qt::Key k) + : modifiers(m), key(k) {} + + // This sort order is used in mouseString() to display sorted wheel bindings + bool operator<(const WheelBindingPrivate& wbp) const + { + if (key != wbp.key) + return key < wbp.key; + return modifiers < wbp.modifiers; + } + }; + + // C l i c k b i n d i n g s + struct ClickBindingPrivate { + const Qt::KeyboardModifiers modifiers; + const Qt::MouseButton button; + const bool doubleClick; + const Qt::MouseButtons buttonsBefore; // only defined when doubleClick is true + const Qt::Key key; + + ClickBindingPrivate(Qt::KeyboardModifiers m, Qt::MouseButton b, bool dc, Qt::MouseButtons bb, Qt::Key k) + : modifiers(m), button(b), doubleClick(dc), buttonsBefore(bb), key(k) {} + + // This sort order is used in mouseString() to display sorted mouse bindings + bool operator<(const ClickBindingPrivate& cbp) const + { + if (key != cbp.key) + return key < cbp.key; + if (buttonsBefore != cbp.buttonsBefore) + return buttonsBefore < cbp.buttonsBefore; + if (modifiers != cbp.modifiers) + return modifiers < cbp.modifiers; + if (button != cbp.button) + return button < cbp.button; + return doubleClick != cbp.doubleClick; } }; #endif - static QString formatClickActionPrivate(ClickActionPrivate cap); + static QString formatClickActionPrivate(ClickBindingPrivate cbp); + static bool isValidShortcutKey(int key); - QMap mouseDescription_; + QMap mouseDescription_; void setDefaultMouseBindings(); void performClickAction(ClickAction ca, const QMouseEvent* const e); - QMap mouseBinding_; - QMap wheelBinding_; - QMap clickBinding_; + QMap mouseBinding_; + QMap wheelBinding_; + QMap clickBinding_; + Qt::Key currentlyPressedKey_; // S n a p s h o t s void initializeSnapshotFormats(); @@ -1253,20 +1286,13 @@ public Q_SLOTS: TileRegion* tileRegion_; // Q G L V i e w e r p o o l -#if QT_VERSION >= 0x040000 static QList QGLViewerPool_; -#else - static QPtrList QGLViewerPool_; -#endif // S t a t e F i l e QString stateFileName_; // H e l p w i n d o w QTabWidget* helpWidget_; - - // I n t e r n a l d e b u g - bool updateGLOK_; }; #endif // QGLVIEWER_QGLVIEWER_H diff --git a/octovis/src/extern/QGLViewer/qglviewer_fr.qm b/octovis/src/extern/QGLViewer/qglviewer_fr.qm index 950597b7350a22f7e354fae39221980b0cff48da..4e9253f0970f24dbb3e2bf710a1be202e75ef56e 100644 GIT binary patch delta 1269 zcmX|=eNa?o6vm%>_ujpG_wL!d!O^1-+A8# z$C$m@NAv=?QNX9S#T4Xh1zZ0YpqT-8E0&U@;3J2Dha$nd2Z8u_C_&l4!YV|}?~B=p zdEN|I!m)b)2q4E}L+}8=jA7%w8NhTAxrOnx{)xQl(?Em@d4C@Pgoly8*-CK&j(!sk zu%F^XnRJ|fSMV`=83^Bp{;WR$Wd?Ufz5=3>m;$expbw^EcPbe=%N*K61@*PeiAKtM zbu*_M>w(A~X4K#SmYSIH)`QfD$c&GX@#rY#+NBJ@9L+9j@1c&fSW|o->5Z@}-zx;- zeq%HG3gLvs&E{>Y0b(z)uWQ>$U{J}>bKkPFbwtXyS*5!2CJ^+sO5GL+BrH=!-uNC+-Ba~zeW;OK)le@P z5em8FwqYl*%*|QTsgM%SJsmVl9fomh^M0jx57+Q68HwUKcLt$kj@)0PC%E@@Nr3kn zu1|L!Fv{HYJbLyGKCnNR49xP6c85}-7QQC!5RvKNyOt69r6v4@*N9lcD{A8lw`dgk z>asegmS$Y7Zkl&&dQt6OwVjaGs>gN5fZ!~FSE-3ekD#O$)4B7)l4KGz{vf>FO~y1& z39Z6aV97^9_mgBG#w46^`O^R1!Y_Nz0gKNF6K5NMfOZXEmkKPnp@|skB{CMxrrSkC z@~mcuQ#e3q5;cddgf`Hv88sg!!F3{UqJ#dO;uAX;laW(m=9Yh`(cSX@Nn7^saw450Effl9b z?B7Jj|oiVY28glWp`ISL;{&NV7{^sef!!03h}2)8euT zWv0IGDizdC>Zk9P(w(_(khSB~X|iEgFOi9C$e>h=>=ri+-10Z?I;mREFrOD zDtZTMD5!#G73VJs-uRp%iz`U^c7 zLa8jU+p4$Os+ID}BG>N=eVF5}=Zra#Ww60cG7ePYWfY?LK^%%W%7&qW@($db&${}J zNldzH&KM#&ifu}0obr;b#_lrt6pH~?TZO|`eZRD;(`QKkpqx@!t!yrGV9%7Javvd+-Mj3Y_NGB5Unxm;OX=4G2#YN#q`lA@D*ZNm~&U?P^{l52k-sgG0 z0sqdxK8q9s@HYWV&wguSumkLlKLG6m@b~7><}VO3`+#ZlAT*u@a*JV0TmekqikXk| z(sDRnPX*Eou`;O_UeeYt8MVI{oa^&1--h4O`enF};&5 zE!zUj8E3cZ4j~BbcJ^okbs{COk*W_UcCaVMh+*0d_AElwxrx1yw~H=l*&AaMK=L_u zESvKDb@pK$DH9#yG@*DPZ#kFw>-PZnh&x$a3mCrOx^)(6ppv^7AtK@$-Wlp6BAvWz z5#iX1`IizO2I-)if2H&eZ5-!!HW87mG`_KrBxG9tjSimwNS+5gv5N1K&j98)zUR9p zz?jO9KbD?-TZr#2As|ke|IR_c)FnLImPYH3g)Iv|A;r!JM{`^hcL^8XA|>-0g-MYb zuzH2b)xijmIIJz$nyi5#`)Vw@@CDTe2lE|iUOx0$xn#31?wn(M@(^2 zVe^Riej5?i7KshwEgaVBBidubex>!z~g!Bc6KP3gO=@)O>3kX*I1}>QxFV=5}p@XxV^mX9gDl*?kv091QOAM7hWmB6#oq3h_#%XQMGo+7%=y?_y=H4bR z^ItVQR~AbJdBei&6(s3vhOS!#q|7oZxMU*iZoveaqoPEduoQB120r3N#DQ+r2(p zd2Jxz^JatvLn9~31y$=Sz5Z}})LbUP>T+-N)VOWyy|x<9W?$82kIh}gjkhSC1lfYKC2X#++$PLpCAV3BgB5qiVf*9^+K6n3LJGY<0@KPOG>)-hijZueL|U ts{1S#g@3As%c2AFw7BISzbD}T4^Vg@sf@M67XLq^4kX2f-Kkrn{{||mUorpy diff --git a/octovis/src/extern/QGLViewer/qglviewer_fr.ts b/octovis/src/extern/QGLViewer/qglviewer_fr.ts index 627360a5..72372d1f 100644 --- a/octovis/src/extern/QGLViewer/qglviewer_fr.ts +++ b/octovis/src/extern/QGLViewer/qglviewer_fr.ts @@ -1,6 +1,6 @@ - + ImageInterface @@ -110,7 +110,7 @@ Affiche ou non la grille XY - Changes camera mode (revolve or fly) + Changes camera mode (observe or fly) CAMERA_MODE action description Change le mode de la caméra (observateur ou vol) @@ -188,10 +188,6 @@ Stereo is not supported on this display. Affichage en stéréo non supporté sur cette machine. - - (no button) - (pas de bouton) - Rotates ROTATE mouse action @@ -263,17 +259,17 @@ Sélectionne - Sets revolve around point + Sets pivot point RAP_FROM_PIXEL click action Définit le point de rotation - Resets revolve around point + Resets pivot point RAP_IS_CENTER click action Restaure le point de rotation - Centers frame + Centers manipulated frame CENTER_FRAME click action Centre le repère manipulé @@ -288,7 +284,7 @@ Affiche toute la scène - Aligns frame + Aligns manipulated frame ALIGN_FRAME click action Aligne le repère manipulé @@ -298,9 +294,9 @@ Aligne la caméra - Camera paths are controlled using %1 (noted <i>Fx</i> below): + Camera paths are controlled using the %1 keys (noted <i>Fx</i> below): Help window key tab camera keys - Les chemins de caméra sont contrôlés avec %1 (noté <i>Fx</i> ci-dessous) : + Les chemins de caméra sont contrôlés avec les touches %1 (notées <i>Fx</i> ci-dessous) : Key(s) @@ -390,7 +386,7 @@ Position %1 sauvegardée - Camera in revolve around mode + Camera in observer mode Feedback message Caméra en mode observateur @@ -523,7 +519,7 @@ &About Help window about title - À propos + À &propos <h1>libQGLViewer</h1><h3>Version %1</h3><br>A versatile 3D viewer based on OpenGL and Qt<br>Copyright 2002-%2 Gilles Debunne<br><code>%3</code> diff --git a/octovis/src/extern/QGLViewer/quaternion.cpp b/octovis/src/extern/QGLViewer/quaternion.cpp index e4062bbf..0c308094 100644 --- a/octovis/src/extern/QGLViewer/quaternion.cpp +++ b/octovis/src/extern/QGLViewer/quaternion.cpp @@ -1,8 +1,8 @@ /**************************************************************************** - Copyright (C) 2002-2013 Gilles Debunne. All rights reserved. + Copyright (C) 2002-2014 Gilles Debunne. All rights reserved. - This file is part of the QGLViewer library version 2.4.0. + This file is part of the QGLViewer library version 2.6.3. http://www.libqglviewer.com - contact@libqglviewer.com @@ -34,32 +34,32 @@ Note that this rotation is not uniquely defined. The selected axis is usually or and \p to, minimizing the rotation angle. This method is robust and can handle small or almost identical vectors. */ Quaternion::Quaternion(const Vec& from, const Vec& to) { - const double epsilon = 1E-10f; - - const double fromSqNorm = from.squaredNorm(); - const double toSqNorm = to.squaredNorm(); - // Identity Quaternion when one vector is null - if ((fromSqNorm < epsilon) || (toSqNorm < epsilon)) - { - q[0]=q[1]=q[2]=0.0; - q[3]=1.0; - } - else - { - Vec axis = cross(from, to); - const double axisSqNorm = axis.squaredNorm(); - - // Aligned vectors, pick any axis, not aligned with from or to - if (axisSqNorm < epsilon) - axis = from.orthogonalVec(); - - double angle = asin(sqrt(axisSqNorm / (fromSqNorm * toSqNorm))); - - if (from*to < 0.0) - angle = M_PI-angle; - - setAxisAngle(axis, angle); - } + const qreal epsilon = 1E-10; + + const qreal fromSqNorm = from.squaredNorm(); + const qreal toSqNorm = to.squaredNorm(); + // Identity Quaternion when one vector is null + if ((fromSqNorm < epsilon) || (toSqNorm < epsilon)) + { + q[0]=q[1]=q[2]=0.0; + q[3]=1.0; + } + else + { + Vec axis = cross(from, to); + const qreal axisSqNorm = axis.squaredNorm(); + + // Aligned vectors, pick any axis, not aligned with from or to + if (axisSqNorm < epsilon) + axis = from.orthogonalVec(); + + qreal angle = asin(sqrt(axisSqNorm / (fromSqNorm * toSqNorm))); + + if (from*to < 0.0) + angle = M_PI-angle; + + setAxisAngle(axis, angle); + } } /*! Returns the image of \p v by the Quaternion inverse() rotation. @@ -67,7 +67,7 @@ Quaternion::Quaternion(const Vec& from, const Vec& to) rotate() performs an inverse transformation. Same as inverse().rotate(v). */ Vec Quaternion::inverseRotate(const Vec& v) const { - return inverse().rotate(v); + return inverse().rotate(v); } /*! Returns the image of \p v by the Quaternion rotation. @@ -75,22 +75,22 @@ Vec Quaternion::inverseRotate(const Vec& v) const See also inverseRotate() and operator*(const Quaternion&, const Vec&). */ Vec Quaternion::rotate(const Vec& v) const { - const double q00 = 2.0l * q[0] * q[0]; - const double q11 = 2.0l * q[1] * q[1]; - const double q22 = 2.0l * q[2] * q[2]; + const qreal q00 = 2.0 * q[0] * q[0]; + const qreal q11 = 2.0 * q[1] * q[1]; + const qreal q22 = 2.0 * q[2] * q[2]; - const double q01 = 2.0l * q[0] * q[1]; - const double q02 = 2.0l * q[0] * q[2]; - const double q03 = 2.0l * q[0] * q[3]; + const qreal q01 = 2.0 * q[0] * q[1]; + const qreal q02 = 2.0 * q[0] * q[2]; + const qreal q03 = 2.0 * q[0] * q[3]; - const double q12 = 2.0l * q[1] * q[2]; - const double q13 = 2.0l * q[1] * q[3]; + const qreal q12 = 2.0 * q[1] * q[2]; + const qreal q13 = 2.0 * q[1] * q[3]; - const double q23 = 2.0l * q[2] * q[3]; + const qreal q23 = 2.0 * q[2] * q[3]; - return Vec((1.0 - q11 - q22)*v[0] + ( q01 - q23)*v[1] + ( q02 + q13)*v[2], - ( q01 + q23)*v[0] + (1.0 - q22 - q00)*v[1] + ( q12 - q03)*v[2], - ( q02 - q13)*v[0] + ( q12 + q03)*v[1] + (1.0 - q11 - q00)*v[2] ); + return Vec((1.0 - q11 - q22)*v[0] + ( q01 - q23)*v[1] + ( q02 + q13)*v[2], + ( q01 + q23)*v[0] + (1.0 - q22 - q00)*v[1] + ( q12 - q03)*v[2], + ( q02 - q13)*v[0] + ( q12 + q03)*v[1] + (1.0 - q11 - q00)*v[2] ); } /*! Set the Quaternion from a (supposedly correct) 3x3 rotation matrix. @@ -101,69 +101,69 @@ Vec Quaternion::rotate(const Vec& v) const setFromRotatedBasis() sets a Quaternion from the three axis of a rotated frame. It actually fills the three columns of a matrix with these rotated basis vectors and calls this method. */ -void Quaternion::setFromRotationMatrix(const double m[3][3]) +void Quaternion::setFromRotationMatrix(const qreal m[3][3]) { - // Compute one plus the trace of the matrix - const double onePlusTrace = 1.0 + m[0][0] + m[1][1] + m[2][2]; - - if (onePlusTrace > 1E-5) - { - // Direct computation - const double s = sqrt(onePlusTrace) * 2.0; - q[0] = (m[2][1] - m[1][2]) / s; - q[1] = (m[0][2] - m[2][0]) / s; - q[2] = (m[1][0] - m[0][1]) / s; - q[3] = 0.25 * s; - } - else - { - // Computation depends on major diagonal term - if ((m[0][0] > m[1][1])&(m[0][0] > m[2][2])) - { - const double s = sqrt(1.0 + m[0][0] - m[1][1] - m[2][2]) * 2.0; - q[0] = 0.25 * s; - q[1] = (m[0][1] + m[1][0]) / s; - q[2] = (m[0][2] + m[2][0]) / s; - q[3] = (m[1][2] - m[2][1]) / s; + // Compute one plus the trace of the matrix + const qreal onePlusTrace = 1.0 + m[0][0] + m[1][1] + m[2][2]; + + if (onePlusTrace > 1E-5) + { + // Direct computation + const qreal s = sqrt(onePlusTrace) * 2.0; + q[0] = (m[2][1] - m[1][2]) / s; + q[1] = (m[0][2] - m[2][0]) / s; + q[2] = (m[1][0] - m[0][1]) / s; + q[3] = 0.25 * s; } - else - if (m[1][1] > m[2][2]) - { - const double s = sqrt(1.0 + m[1][1] - m[0][0] - m[2][2]) * 2.0; - q[0] = (m[0][1] + m[1][0]) / s; - q[1] = 0.25 * s; - q[2] = (m[1][2] + m[2][1]) / s; - q[3] = (m[0][2] - m[2][0]) / s; - } else - { - const double s = sqrt(1.0 + m[2][2] - m[0][0] - m[1][1]) * 2.0; - q[0] = (m[0][2] + m[2][0]) / s; - q[1] = (m[1][2] + m[2][1]) / s; - q[2] = 0.25 * s; - q[3] = (m[0][1] - m[1][0]) / s; - } - } - normalize(); + { + // Computation depends on major diagonal term + if ((m[0][0] > m[1][1])&(m[0][0] > m[2][2])) + { + const qreal s = sqrt(1.0 + m[0][0] - m[1][1] - m[2][2]) * 2.0; + q[0] = 0.25 * s; + q[1] = (m[0][1] + m[1][0]) / s; + q[2] = (m[0][2] + m[2][0]) / s; + q[3] = (m[1][2] - m[2][1]) / s; + } + else + if (m[1][1] > m[2][2]) + { + const qreal s = sqrt(1.0 + m[1][1] - m[0][0] - m[2][2]) * 2.0; + q[0] = (m[0][1] + m[1][0]) / s; + q[1] = 0.25 * s; + q[2] = (m[1][2] + m[2][1]) / s; + q[3] = (m[0][2] - m[2][0]) / s; + } + else + { + const qreal s = sqrt(1.0 + m[2][2] - m[0][0] - m[1][1]) * 2.0; + q[0] = (m[0][2] + m[2][0]) / s; + q[1] = (m[1][2] + m[2][1]) / s; + q[2] = 0.25 * s; + q[3] = (m[0][1] - m[1][0]) / s; + } + } + normalize(); } #ifndef DOXYGEN void Quaternion::setFromRotationMatrix(const float m[3][3]) { - qWarning("setFromRotationMatrix now waits for a double[3][3] parameter"); + qWarning("setFromRotationMatrix now expects a double[3][3] parameter"); - double mat[3][3]; - for (int i=0; i<3; ++i) - for (int j=0; j<3; ++j) - mat[i][j] = double(m[i][j]); + qreal mat[3][3]; + for (int i=0; i<3; ++i) + for (int j=0; j<3; ++j) + mat[i][j] = qreal(m[i][j]); - setFromRotationMatrix(mat); + setFromRotationMatrix(mat); } void Quaternion::setFromRotatedBase(const Vec& X, const Vec& Y, const Vec& Z) { - qWarning("setFromRotatedBase is deprecated, use setFromRotatedBasis instead"); - setFromRotatedBasis(X,Y,Z); + qWarning("setFromRotatedBase is deprecated, use setFromRotatedBasis instead"); + setFromRotatedBasis(X,Y,Z); } #endif @@ -181,36 +181,36 @@ void Quaternion::setFromRotatedBase(const Vec& X, const Vec& Y, const Vec& Z) See also setFromRotationMatrix() and Quaternion(const Vec&, const Vec&). */ void Quaternion::setFromRotatedBasis(const Vec& X, const Vec& Y, const Vec& Z) { - double m[3][3]; - double normX = X.norm(); - double normY = Y.norm(); - double normZ = Z.norm(); - - for (int i=0; i<3; ++i) - { - m[i][0] = X[i] / normX; - m[i][1] = Y[i] / normY; - m[i][2] = Z[i] / normZ; - } - - setFromRotationMatrix(m); + qreal m[3][3]; + qreal normX = X.norm(); + qreal normY = Y.norm(); + qreal normZ = Z.norm(); + + for (int i=0; i<3; ++i) + { + m[i][0] = X[i] / normX; + m[i][1] = Y[i] / normY; + m[i][2] = Z[i] / normZ; + } + + setFromRotationMatrix(m); } /*! Returns the axis vector and the angle (in radians) of the rotation represented by the Quaternion. See the axis() and angle() documentations. */ -void Quaternion::getAxisAngle(Vec& axis, float& angle) const +void Quaternion::getAxisAngle(Vec& axis, qreal& angle) const { - angle = 2.0*acos(q[3]); - axis = Vec(q[0], q[1], q[2]); - const double sinus = axis.norm(); - if (sinus > 1E-8) - axis /= sinus; - - if (angle > M_PI) - { - angle = 2.0*M_PI - angle; - axis = -axis; - } + angle = 2.0 * acos(q[3]); + axis = Vec(q[0], q[1], q[2]); + const qreal sinus = axis.norm(); + if (sinus > 1E-8) + axis /= sinus; + + if (angle > M_PI) + { + angle = 2.0 * qreal(M_PI) - angle; + axis = -axis; + } } /*! Returns the normalized axis direction of the rotation represented by the Quaternion. @@ -218,11 +218,11 @@ void Quaternion::getAxisAngle(Vec& axis, float& angle) const It is null for an identity Quaternion. See also angle() and getAxisAngle(). */ Vec Quaternion::axis() const { - Vec res = Vec(q[0], q[1], q[2]); - const double sinus = res.norm(); - if (sinus > 1E-8) - res /= sinus; - return (acos(q[3]) <= M_PI/2.0) ? res : -res; + Vec res = Vec(q[0], q[1], q[2]); + const qreal sinus = res.norm(); + if (sinus > 1E-8) + res /= sinus; + return (acos(q[3]) <= M_PI/2.0) ? res : -res; } /*! Returns the angle (in radians) of the rotation represented by the Quaternion. @@ -231,10 +231,10 @@ Vec Quaternion::axis() const axis() direction. See also axis() and getAxisAngle(). */ -double Quaternion::angle() const +qreal Quaternion::angle() const { - const double angle = 2.0 * acos(q[3]); - return (angle <= M_PI) ? angle : 2.0*M_PI - angle; + const qreal angle = 2.0 * acos(q[3]); + return (angle <= M_PI) ? angle : 2.0*M_PI - angle; } /*! Returns an XML \c QDomElement that represents the Quaternion. @@ -255,12 +255,12 @@ double Quaternion::angle() const See also Frame::domElement(), Camera::domElement(), KeyFrameInterpolator::domElement()... */ QDomElement Quaternion::domElement(const QString& name, QDomDocument& document) const { - QDomElement de = document.createElement(name); - de.setAttribute("q0", QString::number(q[0])); - de.setAttribute("q1", QString::number(q[1])); - de.setAttribute("q2", QString::number(q[2])); - de.setAttribute("q3", QString::number(q[3])); - return de; + QDomElement de = document.createElement(name); + de.setAttribute("q0", QString::number(q[0])); + de.setAttribute("q1", QString::number(q[1])); + de.setAttribute("q2", QString::number(q[2])); + de.setAttribute("q3", QString::number(q[3])); + return de; } /*! Restores the Quaternion state from a \c QDomElement created by domElement(). @@ -272,8 +272,8 @@ QDomElement Quaternion::domElement(const QString& name, QDomDocument& document) See also the Quaternion(const QDomElement&) constructor. */ void Quaternion::initFromDOMElement(const QDomElement& element) { - Quaternion q(element); - *this = q; + Quaternion q(element); + *this = q; } /*! Constructs a Quaternion from a \c QDomElement representing an XML code of the form @@ -285,14 +285,10 @@ void Quaternion::initFromDOMElement(const QDomElement& element) See also domElement() and initFromDOMElement(). */ Quaternion::Quaternion(const QDomElement& element) { - QStringList attribute; - attribute << "q0" << "q1" << "q2" << "q3"; -#if QT_VERSION >= 0x040000 - for (int i=0; i namespace qglviewer { - /*! \brief The Quaternion class represents 3D rotations and orientations. +/*! \brief The Quaternion class represents 3D rotations and orientations. \class Quaternion quaternion.h QGLViewer/quaternion.h The Quaternion is an appropriate (although not very intuitive) representation for 3D rotations and @@ -51,7 +51,7 @@ namespace qglviewer {

Internal representation

The internal representation of a Quaternion corresponding to a rotation around axis \c axis, with an angle - \c alpha is made of four doubles q[i]: + \c alpha is made of four qreals (i.e. doubles) q[i]: \code {q[0],q[1],q[2]} = sin(alpha/2) * {axis[0],axis[1],axis[2]} q[3] = cos(alpha/2) @@ -63,94 +63,94 @@ namespace qglviewer { See also the Vec and Frame classes' documentations. \nosubgrouping */ - class QGLVIEWER_EXPORT Quaternion +class QGLVIEWER_EXPORT Quaternion +{ +public: + /*! @name Defining a Quaternion */ + //@{ + /*! Default constructor, builds an identity rotation. */ + Quaternion() + { q[0]=q[1]=q[2]=0.0; q[3]=1.0; } + + /*! Constructor from rotation axis (non null) and angle (in radians). See also setAxisAngle(). */ + Quaternion(const Vec& axis, qreal angle) { - public: - /*! @name Defining a Quaternion */ - //@{ - /*! Default constructor, builds an identity rotation. */ - Quaternion() - { q[0]=q[1]=q[2]=0.0; q[3]=1.0; } - - /*! Constructor from rotation axis (non null) and angle (in radians). See also setAxisAngle(). */ - Quaternion(const Vec& axis, double angle) - { - setAxisAngle(axis, angle); - } + setAxisAngle(axis, angle); + } - Quaternion(const Vec& from, const Vec& to); + Quaternion(const Vec& from, const Vec& to); - /*! Constructor from the four values of a Quaternion. First three values are axis*sin(angle/2) and + /*! Constructor from the four values of a Quaternion. First three values are axis*sin(angle/2) and last one is cos(angle/2). \attention The identity Quaternion is Quaternion(0,0,0,1) and \e not Quaternion(0,0,0,0) (which is not unitary). The default Quaternion() creates such identity Quaternion. */ - Quaternion(double q0, double q1, double q2, double q3) - { q[0]=q0; q[1]=q1; q[2]=q2; q[3]=q3; } + Quaternion(qreal q0, qreal q1, qreal q2, qreal q3) + { q[0]=q0; q[1]=q1; q[2]=q2; q[3]=q3; } - /*! Copy constructor. */ - Quaternion(const Quaternion& Q) - { for (int i=0; i<4; ++i) q[i] = Q.q[i]; } + /*! Copy constructor. */ + Quaternion(const Quaternion& Q) + { for (int i=0; i<4; ++i) q[i] = Q.q[i]; } - /*! Equal operator. */ - Quaternion& operator=(const Quaternion& Q) - { - for (int i=0; i<4; ++i) - q[i] = Q.q[i]; - return (*this); - } + /*! Equal operator. */ + Quaternion& operator=(const Quaternion& Q) + { + for (int i=0; i<4; ++i) + q[i] = Q.q[i]; + return (*this); + } - /*! Sets the Quaternion as a rotation of axis \p axis and angle \p angle (in radians). + /*! Sets the Quaternion as a rotation of axis \p axis and angle \p angle (in radians). \p axis does not need to be normalized. A null \p axis will result in an identity Quaternion. */ - void setAxisAngle(const Vec& axis, double angle) + void setAxisAngle(const Vec& axis, qreal angle) + { + const qreal norm = axis.norm(); + if (norm < 1E-8) + { + // Null rotation + q[0] = 0.0; q[1] = 0.0; q[2] = 0.0; q[3] = 1.0; + } + else { - const double norm = axis.norm(); - if (norm < 1E-8) - { - // Null rotation - q[0] = 0.0; q[1] = 0.0; q[2] = 0.0; q[3] = 1.0; - } - else - { - const double sin_half_angle = sin(angle / 2.0); - q[0] = sin_half_angle*axis[0]/norm; - q[1] = sin_half_angle*axis[1]/norm; - q[2] = sin_half_angle*axis[2]/norm; - q[3] = cos(angle / 2.0); - } + const qreal sin_half_angle = sin(angle / 2.0); + q[0] = sin_half_angle*axis[0]/norm; + q[1] = sin_half_angle*axis[1]/norm; + q[2] = sin_half_angle*axis[2]/norm; + q[3] = cos(angle / 2.0); } + } - /*! Sets the Quaternion value. See the Quaternion(double, double, double, double) constructor documentation. */ - void setValue(double q0, double q1, double q2, double q3) - { q[0]=q0; q[1]=q1; q[2]=q2; q[3]=q3; } + /*! Sets the Quaternion value. See the Quaternion(qreal, qreal, qreal, qreal) constructor documentation. */ + void setValue(qreal q0, qreal q1, qreal q2, qreal q3) + { q[0]=q0; q[1]=q1; q[2]=q2; q[3]=q3; } #ifndef DOXYGEN - void setFromRotationMatrix(const float m[3][3]); - void setFromRotatedBase(const Vec& X, const Vec& Y, const Vec& Z); + void setFromRotationMatrix(const float m[3][3]); + void setFromRotatedBase(const Vec& X, const Vec& Y, const Vec& Z); #endif - void setFromRotationMatrix(const double m[3][3]); - void setFromRotatedBasis(const Vec& X, const Vec& Y, const Vec& Z); - //@} + void setFromRotationMatrix(const qreal m[3][3]); + void setFromRotatedBasis(const Vec& X, const Vec& Y, const Vec& Z); + //@} - /*! @name Accessing values */ - //@{ - Vec axis() const; - double angle() const; - void getAxisAngle(Vec& axis, float& angle) const; + /*! @name Accessing values */ + //@{ + Vec axis() const; + qreal angle() const; + void getAxisAngle(Vec& axis, qreal& angle) const; - /*! Bracket operator, with a constant return value. \p i must range in [0..3]. See the Quaternion(double, double, double, double) documentation. */ - double operator[](int i) const { return q[i]; } + /*! Bracket operator, with a constant return value. \p i must range in [0..3]. See the Quaternion(qreal, qreal, qreal, qreal) documentation. */ + qreal operator[](int i) const { return q[i]; } - /*! Bracket operator returning an l-value. \p i must range in [0..3]. See the Quaternion(double, double, double, double) documentation. */ - double& operator[](int i) { return q[i]; } - //@} + /*! Bracket operator returning an l-value. \p i must range in [0..3]. See the Quaternion(qreal, qreal, qreal, qreal) documentation. */ + qreal& operator[](int i) { return q[i]; } + //@} - /*! @name Rotation computations */ - //@{ - /*! Returns the composition of the \p a and \p b rotations. + /*! @name Rotation computations */ + //@{ + /*! Returns the composition of the \p a and \p b rotations. The order is important. When applied to a Vec \c v (see operator*(const Quaternion&, const Vec&) and rotate()) the resulting Quaternion acts as if \p b was applied first and then \p a was @@ -161,55 +161,55 @@ namespace qglviewer { \attention For efficiency reasons, the resulting Quaternion is not normalized. Use normalize() in case of numerical drift with small rotation composition. */ - friend Quaternion operator*(const Quaternion& a, const Quaternion& b) - { - return Quaternion(a.q[3]*b.q[0] + b.q[3]*a.q[0] + a.q[1]*b.q[2] - a.q[2]*b.q[1], + friend Quaternion operator*(const Quaternion& a, const Quaternion& b) + { + return Quaternion(a.q[3]*b.q[0] + b.q[3]*a.q[0] + a.q[1]*b.q[2] - a.q[2]*b.q[1], a.q[3]*b.q[1] + b.q[3]*a.q[1] + a.q[2]*b.q[0] - a.q[0]*b.q[2], a.q[3]*b.q[2] + b.q[3]*a.q[2] + a.q[0]*b.q[1] - a.q[1]*b.q[0], a.q[3]*b.q[3] - b.q[0]*a.q[0] - a.q[1]*b.q[1] - a.q[2]*b.q[2]); - } + } - /*! Quaternion rotation is composed with \p q. + /*! Quaternion rotation is composed with \p q. See operator*(), since this is equivalent to \c this = \c this * \p q. \note For efficiency reasons, the resulting Quaternion is not normalized. You may normalize() it after each application in case of numerical drift. */ - Quaternion& operator*=(const Quaternion &q) - { - *this = (*this)*q; - return *this; - } + Quaternion& operator*=(const Quaternion &q) + { + *this = (*this)*q; + return *this; + } - /*! Returns the image of \p v by the rotation \p q. + /*! Returns the image of \p v by the rotation \p q. Same as q.rotate(v). See rotate() and inverseRotate(). */ - friend Vec operator*(const Quaternion& q, const Vec& v) - { - return q.rotate(v); - } + friend Vec operator*(const Quaternion& q, const Vec& v) + { + return q.rotate(v); + } - Vec rotate(const Vec& v) const; - Vec inverseRotate(const Vec& v) const; - //@} + Vec rotate(const Vec& v) const; + Vec inverseRotate(const Vec& v) const; + //@} - /*! @name Inversion */ - //@{ - /*! Returns the inverse Quaternion (inverse rotation). + /*! @name Inversion */ + //@{ + /*! Returns the inverse Quaternion (inverse rotation). Result has a negated axis() direction and the same angle(). A composition (see operator*()) of a Quaternion and its inverse() results in an identity function. Use invert() to actually modify the Quaternion. */ - Quaternion inverse() const { return Quaternion(-q[0], -q[1], -q[2], q[3]); } + Quaternion inverse() const { return Quaternion(-q[0], -q[1], -q[2], q[3]); } - /*! Inverses the Quaternion (same rotation angle(), but negated axis()). + /*! Inverses the Quaternion (same rotation angle(), but negated axis()). See also inverse(). */ - void invert() { q[0] = -q[0]; q[1] = -q[1]; q[2] = -q[2]; } + void invert() { q[0] = -q[0]; q[1] = -q[1]; q[2] = -q[2]; } - /*! Negates all the coefficients of the Quaternion. + /*! Negates all the coefficients of the Quaternion. This results in an other representation of the \e same rotation (opposite rotation angle, but with a negated axis direction: the two cancel out). However, note that the results of axis() and @@ -217,92 +217,92 @@ namespace qglviewer { This method is mainly useful for Quaternion interpolation, so that the spherical interpolation takes the shortest path on the unit sphere. See slerp() for details. */ - void negate() { invert(); q[3] = -q[3]; } + void negate() { invert(); q[3] = -q[3]; } - /*! Normalizes the Quaternion coefficients. + /*! Normalizes the Quaternion coefficients. This method should not need to be called since we only deal with unit Quaternions. This is however useful to prevent numerical drifts, especially with small rotational increments. See also normalized(). */ - double normalize() - { - const double norm = sqrt(q[0]*q[0] + q[1]*q[1] + q[2]*q[2] + q[3]*q[3]); - for (int i=0; i<4; ++i) - q[i] /= norm; - return norm; - } + qreal normalize() + { + const qreal norm = sqrt(q[0]*q[0] + q[1]*q[1] + q[2]*q[2] + q[3]*q[3]); + for (int i=0; i<4; ++i) + q[i] /= norm; + return norm; + } - /*! Returns a normalized version of the Quaternion. + /*! Returns a normalized version of the Quaternion. See also normalize(). */ - Quaternion normalized() const - { - double Q[4]; - const double norm = sqrt(q[0]*q[0] + q[1]*q[1] + q[2]*q[2] + q[3]*q[3]); - for (int i=0; i<4; ++i) - Q[i] = q[i] / norm; - return Quaternion(Q[0], Q[1], Q[2], Q[3]); - } - //@} - - - /*! @name Associated matrix */ - //@{ - const GLdouble* matrix() const; - void getMatrix(GLdouble m[4][4]) const; - void getMatrix(GLdouble m[16]) const; - - void getRotationMatrix(float m[3][3]) const; - - const GLdouble* inverseMatrix() const; - void getInverseMatrix(GLdouble m[4][4]) const; - void getInverseMatrix(GLdouble m[16]) const; - - void getInverseRotationMatrix(float m[3][3]) const; - //@} - - - /*! @name Slerp interpolation */ - //@{ - static Quaternion slerp(const Quaternion& a, const Quaternion& b, float t, bool allowFlip=true); - static Quaternion squad(const Quaternion& a, const Quaternion& tgA, const Quaternion& tgB, const Quaternion& b, float t); - /*! Returns the "dot" product of \p a and \p b: a[0]*b[0] + a[1]*b[1] + a[2]*b[2] + a[3]*b[3]. */ - static double dot(const Quaternion& a, const Quaternion& b) { return a[0]*b[0] + a[1]*b[1] + a[2]*b[2] + a[3]*b[3]; } - - Quaternion log(); - Quaternion exp(); - static Quaternion lnDif(const Quaternion& a, const Quaternion& b); - static Quaternion squadTangent(const Quaternion& before, const Quaternion& center, const Quaternion& after); - //@} - - /*! @name Random Quaternion */ - //@{ - static Quaternion randomQuaternion(); - //@} - - /*! @name XML representation */ - //@{ - explicit Quaternion(const QDomElement& element); - QDomElement domElement(const QString& name, QDomDocument& document) const; - void initFromDOMElement(const QDomElement& element); - //@} + Quaternion normalized() const + { + qreal Q[4]; + const qreal norm = sqrt(q[0]*q[0] + q[1]*q[1] + q[2]*q[2] + q[3]*q[3]); + for (int i=0; i<4; ++i) + Q[i] = q[i] / norm; + return Quaternion(Q[0], Q[1], Q[2], Q[3]); + } + //@} + + + /*! @name Associated matrix */ + //@{ + const GLdouble* matrix() const; + void getMatrix(GLdouble m[4][4]) const; + void getMatrix(GLdouble m[16]) const; + + void getRotationMatrix(qreal m[3][3]) const; + + const GLdouble* inverseMatrix() const; + void getInverseMatrix(GLdouble m[4][4]) const; + void getInverseMatrix(GLdouble m[16]) const; + + void getInverseRotationMatrix(qreal m[3][3]) const; + //@} + + + /*! @name Slerp interpolation */ + //@{ + static Quaternion slerp(const Quaternion& a, const Quaternion& b, qreal t, bool allowFlip=true); + static Quaternion squad(const Quaternion& a, const Quaternion& tgA, const Quaternion& tgB, const Quaternion& b, qreal t); + /*! Returns the "dot" product of \p a and \p b: a[0]*b[0] + a[1]*b[1] + a[2]*b[2] + a[3]*b[3]. */ + static qreal dot(const Quaternion& a, const Quaternion& b) { return a[0]*b[0] + a[1]*b[1] + a[2]*b[2] + a[3]*b[3]; } + + Quaternion log(); + Quaternion exp(); + static Quaternion lnDif(const Quaternion& a, const Quaternion& b); + static Quaternion squadTangent(const Quaternion& before, const Quaternion& center, const Quaternion& after); + //@} + + /*! @name Random Quaternion */ + //@{ + static Quaternion randomQuaternion(); + //@} + + /*! @name XML representation */ + //@{ + explicit Quaternion(const QDomElement& element); + QDomElement domElement(const QString& name, QDomDocument& document) const; + void initFromDOMElement(const QDomElement& element); + //@} #ifdef DOXYGEN - /*! @name Output stream */ - //@{ - /*! Output stream operator. Enables debugging code like: + /*! @name Output stream */ + //@{ + /*! Output stream operator. Enables debugging code like: \code Quaternion rot(...); cout << "Rotation=" << rot << endl; \endcode */ - std::ostream& operator<<(std::ostream& o, const qglviewer::Vec&); - //@} + std::ostream& operator<<(std::ostream& o, const qglviewer::Vec&); + //@} #endif - private: - /*! The internal data representation is private, use operator[] to access values. */ - double q[4]; - }; +private: + /*! The internal data representation is private, use operator[] to access values. */ + qreal q[4]; +}; } // namespace diff --git a/octovis/src/extern/QGLViewer/saveSnapshot.cpp b/octovis/src/extern/QGLViewer/saveSnapshot.cpp index a29d3f3e..4a53b8bb 100644 --- a/octovis/src/extern/QGLViewer/saveSnapshot.cpp +++ b/octovis/src/extern/QGLViewer/saveSnapshot.cpp @@ -1,8 +1,8 @@ /**************************************************************************** - Copyright (C) 2002-2013 Gilles Debunne. All rights reserved. + Copyright (C) 2002-2014 Gilles Debunne. All rights reserved. - This file is part of the QGLViewer library version 2.4.0. + This file is part of the QGLViewer library version 2.6.3. http://www.libqglviewer.com - contact@libqglviewer.com @@ -23,30 +23,14 @@ #include "qglviewer.h" #ifndef NO_VECTORIAL_RENDER -# if QT_VERSION >= 0x040000 # include "ui_VRenderInterface.h" -# else -# include -# include -# include "VRenderInterface.Qt3.h" -# endif -# include "VRender/VRender.h" +# include "VRender/VRender.h" #endif -#if QT_VERSION >= 0x040000 -# include "ui_ImageInterface.h" -#else -# include -# include -# include "ImageInterface.Qt3.h" -#endif +#include "ui_ImageInterface.h" // Output format list -#if QT_VERSION < 0x040000 -# include -#else # include -#endif #include #include @@ -73,18 +57,14 @@ static QMap extension; /*! Sets snapshotFileName(). */ void QGLViewer::setSnapshotFileName(const QString& name) { -#if QT_VERSION >= 0x040000 - snapshotFileName_ = QFileInfo(name).absoluteFilePath(); -#else - snapshotFileName_ = QFileInfo(name).absFilePath(); -#endif + snapshotFileName_ = QFileInfo(name).absoluteFilePath(); } #ifndef DOXYGEN const QString& QGLViewer::snapshotFilename() const { - qWarning("snapshotFilename is deprecated. Use snapshotFileName() (uppercase N) instead."); - return snapshotFileName(); + qWarning("snapshotFilename is deprecated. Use snapshotFileName() (uppercase N) instead."); + return snapshotFileName(); } #endif @@ -96,19 +76,13 @@ Then calls setSnapshotFormat() with the selected one (unless the user cancels). Returns \c false if the user presses the Cancel button and \c true otherwise. */ bool QGLViewer::openSnapshotFormatDialog() { - bool ok = false; -#if QT_VERSION >= 0x040000 - QStringList list = formats.split(";;", QString::SkipEmptyParts); - int current = list.indexOf(FDFormatString[snapshotFormat()]); - QString format = QInputDialog::getItem(this, "Snapshot format", "Select a snapshot format", list, current, false, &ok); -#else - QStringList list = QStringList::split(";;", formats); - int current = list.findIndex(FDFormatString[snapshotFormat()]); - QString format = QInputDialog::getItem("Snapshot format", "Select a snapshot format", list, current, false, &ok, this); -#endif - if (ok) - setSnapshotFormat(Qtformat[format]); - return ok; + bool ok = false; + QStringList list = formats.split(";;", QString::SkipEmptyParts); + int current = list.indexOf(FDFormatString[snapshotFormat()]); + QString format = QInputDialog::getItem(this, "Snapshot format", "Select a snapshot format", list, current, false, &ok); + if (ok) + setSnapshotFormat(Qtformat[format]); + return ok; } @@ -116,476 +90,398 @@ bool QGLViewer::openSnapshotFormatDialog() // saveSnapshot dialog. Initialize snapshotFormat() to the first one. void QGLViewer::initializeSnapshotFormats() { -#if QT_VERSION >= 0x040000 - QList list = QImageWriter::supportedImageFormats(); - QStringList formatList; - for (int i=0; i < list.size(); ++i) - formatList << QString(list.at(i).toUpper()); -#else - QStringList formatList = QImage::outputFormatList(); -#endif - // qWarning("Available image formats: "); - // QStringList::Iterator it = formatList.begin(); - // while( it != formatList.end() ) - // qWarning((*it++).); QT4 change this. qWarning no longer accepts QString + QList list = QImageWriter::supportedImageFormats(); + QStringList formatList; + for (int i=0; i < list.size(); ++i) + formatList << QString(list.at(i).toUpper()); + // qWarning("Available image formats: "); + // QStringList::Iterator it = formatList.begin(); + // while( it != formatList.end() ) + // qWarning((*it++).); QT4 change this. qWarning no longer accepts QString #ifndef NO_VECTORIAL_RENDER - // We add the 3 vectorial formats to the list - formatList += "EPS"; - formatList += "PS"; - formatList += "XFIG"; + // We add the 3 vectorial formats to the list + formatList += "EPS"; + formatList += "PS"; + formatList += "XFIG"; #endif - // Check that the interesting formats are available and add them in "formats" - // Unused formats: XPM XBM PBM PGM - QStringList QtText, MenuText, Ext; - QtText += "JPEG"; MenuText += "JPEG (*.jpg)"; Ext += "jpg"; - QtText += "PNG"; MenuText += "PNG (*.png)"; Ext += "png"; - QtText += "EPS"; MenuText += "Encapsulated Postscript (*.eps)"; Ext += "eps"; - QtText += "PS"; MenuText += "Postscript (*.ps)"; Ext += "ps"; - QtText += "PPM"; MenuText += "24bit RGB Bitmap (*.ppm)"; Ext += "ppm"; - QtText += "BMP"; MenuText += "Windows Bitmap (*.bmp)"; Ext += "bmp"; - QtText += "XFIG"; MenuText += "XFig (*.fig)"; Ext += "fig"; - -#if QT_VERSION < 0x030000 - QStringList::Iterator itText = QtText.begin(); - QStringList::Iterator itMenu = MenuText.begin(); - QStringList::Iterator itExt = Ext.begin(); -#else - QStringList::iterator itText = QtText.begin(); - QStringList::iterator itMenu = MenuText.begin(); - QStringList::iterator itExt = Ext.begin(); -#endif - while (itText != QtText.end()) - { - //QMessageBox::information(this, "Snapshot ", "Trying format\n"+(*itText)); - if (formatList.contains((*itText))) + // Check that the interesting formats are available and add them in "formats" + // Unused formats: XPM XBM PBM PGM + QStringList QtText, MenuText, Ext; + QtText += "JPEG"; MenuText += "JPEG (*.jpg)"; Ext += "jpg"; + QtText += "PNG"; MenuText += "PNG (*.png)"; Ext += "png"; + QtText += "EPS"; MenuText += "Encapsulated Postscript (*.eps)"; Ext += "eps"; + QtText += "PS"; MenuText += "Postscript (*.ps)"; Ext += "ps"; + QtText += "PPM"; MenuText += "24bit RGB Bitmap (*.ppm)"; Ext += "ppm"; + QtText += "BMP"; MenuText += "Windows Bitmap (*.bmp)"; Ext += "bmp"; + QtText += "XFIG"; MenuText += "XFig (*.fig)"; Ext += "fig"; + + QStringList::iterator itText = QtText.begin(); + QStringList::iterator itMenu = MenuText.begin(); + QStringList::iterator itExt = Ext.begin(); + + while (itText != QtText.end()) { - //QMessageBox::information(this, "Snapshot ", "Recognized format\n"+(*itText)); - if (formats.isEmpty()) - setSnapshotFormat(*itText); - else - formats += ";;"; - formats += (*itMenu); - Qtformat[(*itMenu)] = (*itText); - FDFormatString[(*itText)] = (*itMenu); - extension[(*itText)] = (*itExt); + //QMessageBox::information(this, "Snapshot ", "Trying format\n"+(*itText)); + if (formatList.contains((*itText))) + { + //QMessageBox::information(this, "Snapshot ", "Recognized format\n"+(*itText)); + if (formats.isEmpty()) + setSnapshotFormat(*itText); + else + formats += ";;"; + formats += (*itMenu); + Qtformat[(*itMenu)] = (*itText); + FDFormatString[(*itText)] = (*itMenu); + extension[(*itText)] = (*itExt); + } + // Synchronize parsing + itText++; + itMenu++; + itExt++; } - // Synchronize parsing - itText++; - itMenu++; - itExt++; - } } // Returns false if the user refused to use the fileName static bool checkFileName(QString& fileName, QWidget* widget, const QString& snapshotFormat) { - if (fileName.isEmpty()) - return false; + if (fileName.isEmpty()) + return false; - // Check that extension has been provided - QFileInfo info(fileName); + // Check that extension has been provided + QFileInfo info(fileName); -#if QT_VERSION >= 0x040000 - if (info.suffix().isEmpty()) -#else - if (info.extension(false).isEmpty()) -#endif - { - // No extension given. Silently add one - if (fileName.right(1) != ".") - fileName += "."; - fileName += extension[snapshotFormat]; - info.setFile(fileName); - } -#if QT_VERSION >= 0x040000 - else if (info.suffix() != extension[snapshotFormat]) -#else - else if (info.extension(false) != extension[snapshotFormat]) -#endif - { - // Extension is not appropriate. Propose a modification -#if QT_VERSION >= 0x040000 - QString modifiedName = info.absolutePath() + '/' + info.baseName() + "." + extension[snapshotFormat]; -#else -# if QT_VERSION >= 0x030000 - QString modifiedName = info.dirPath() + '/' + info.baseName(true) + '.' + extension[snapshotFormat]; -# else - QString modifiedName = info.dirPath() + '/' + info.baseName() + '.' + extension[snapshotFormat]; -# endif -#endif - QFileInfo modifInfo(modifiedName); - int i=(QMessageBox::warning(widget,"Wrong extension", - info.fileName()+" has a wrong extension.\nSave as "+modifInfo.fileName()+" instead ?", - QMessageBox::Yes, - QMessageBox::No, - QMessageBox::Cancel)); - if (i==QMessageBox::Cancel) - return false; - - if (i==QMessageBox::Yes) + if (info.suffix().isEmpty()) + { + // No extension given. Silently add one + if (fileName.right(1) != ".") + fileName += "."; + fileName += extension[snapshotFormat]; + info.setFile(fileName); + } + else if (info.suffix() != extension[snapshotFormat]) { - fileName = modifiedName; - info.setFile(fileName); + // Extension is not appropriate. Propose a modification + QString modifiedName = info.absolutePath() + '/' + info.baseName() + "." + extension[snapshotFormat]; + QFileInfo modifInfo(modifiedName); + int i=(QMessageBox::warning(widget,"Wrong extension", + info.fileName()+" has a wrong extension.\nSave as "+modifInfo.fileName()+" instead ?", + QMessageBox::Yes, + QMessageBox::No, + QMessageBox::Cancel)); + if (i==QMessageBox::Cancel) + return false; + + if (i==QMessageBox::Yes) + { + fileName = modifiedName; + info.setFile(fileName); + } } - } - return true; + return true; } #ifndef NO_VECTORIAL_RENDER // static void drawVectorial(void* param) void drawVectorial(void* param) { - ( (QGLViewer*) param )->drawVectorial(); + ( (QGLViewer*) param )->drawVectorial(); } #ifndef DOXYGEN class ProgressDialog { public: - static void showProgressDialog(QGLWidget* parent); - static void updateProgress(float progress, const QString& stepString); - static void hideProgressDialog(); + static void showProgressDialog(QGLWidget* parent); + static void updateProgress(float progress, const QString& stepString); + static void hideProgressDialog(); private: - static QProgressDialog* progressDialog; + static QProgressDialog* progressDialog; }; QProgressDialog* ProgressDialog::progressDialog = NULL; void ProgressDialog::showProgressDialog(QGLWidget* parent) { - progressDialog = new QProgressDialog(parent); -#if QT_VERSION >= 0x040000 - progressDialog->setWindowTitle("Image rendering progress"); -#else - progressDialog->setCaption("Image rendering progress"); -#endif - progressDialog->setMinimumSize(300, 40); - progressDialog->setCancelButton(NULL); - progressDialog->show(); + progressDialog = new QProgressDialog(parent); + progressDialog->setWindowTitle("Image rendering progress"); + progressDialog->setMinimumSize(300, 40); + progressDialog->setCancelButton(NULL); + progressDialog->show(); } void ProgressDialog::updateProgress(float progress, const QString& stepString) { -#if QT_VERSION >= 0x040000 - progressDialog->setValue(int(progress*100)); -#else - progressDialog->setProgress(int(progress*100)); -#endif - QString message(stepString); - if (message.length() > 33) - message = message.left(17) + "..." + message.right(12); - progressDialog->setLabelText(message); - progressDialog->update(); - qApp->processEvents(); + progressDialog->setValue(int(progress*100)); + QString message(stepString); + if (message.length() > 33) + message = message.left(17) + "..." + message.right(12); + progressDialog->setLabelText(message); + progressDialog->update(); + qApp->processEvents(); } void ProgressDialog::hideProgressDialog() { - progressDialog->close(); - delete progressDialog; - progressDialog = NULL; + progressDialog->close(); + delete progressDialog; + progressDialog = NULL; } -#if QT_VERSION >= 0x040000 class VRenderInterface: public QDialog, public Ui::VRenderInterface { - public: VRenderInterface(QWidget *parent) : QDialog(parent) { setupUi(this); } +public: VRenderInterface(QWidget *parent) : QDialog(parent) { setupUi(this); } }; -#endif -#endif +#endif //DOXYGEN // Pops-up a vectorial output option dialog box and save to fileName // Returns -1 in case of Cancel, 0 for success and (todo) error code in case of problem. static int saveVectorialSnapshot(const QString& fileName, QGLWidget* widget, const QString& snapshotFormat) { - static VRenderInterface* VRinterface = NULL; + static VRenderInterface* VRinterface = NULL; - if (!VRinterface) -#if QT_VERSION >= 0x030000 - VRinterface = new VRenderInterface(widget); -#else - VRinterface = new VRenderInterface(widget, "", true); // Make the dialog modal -#endif + if (!VRinterface) + VRinterface = new VRenderInterface(widget); - - // Configure interface according to selected snapshotFormat - if (snapshotFormat == "XFIG") - { - VRinterface->tightenBBox->setEnabled(false); - VRinterface->colorBackground->setEnabled(false); - } - else - { - VRinterface->tightenBBox->setEnabled(true); - VRinterface->colorBackground->setEnabled(true); - } - - if (VRinterface->exec() == QDialog::Rejected) - return -1; - - vrender::VRenderParams vparams; - vparams.setFilename(fileName); - - if (snapshotFormat == "EPS") vparams.setFormat(vrender::VRenderParams::EPS); - if (snapshotFormat == "PS") vparams.setFormat(vrender::VRenderParams::PS); - if (snapshotFormat == "XFIG") vparams.setFormat(vrender::VRenderParams::XFIG); - - vparams.setOption(vrender::VRenderParams::CullHiddenFaces, !(VRinterface->includeHidden->isChecked())); - vparams.setOption(vrender::VRenderParams::OptimizeBackFaceCulling, VRinterface->cullBackFaces->isChecked()); - vparams.setOption(vrender::VRenderParams::RenderBlackAndWhite, VRinterface->blackAndWhite->isChecked()); - vparams.setOption(vrender::VRenderParams::AddBackground, VRinterface->colorBackground->isChecked()); - vparams.setOption(vrender::VRenderParams::TightenBoundingBox, VRinterface->tightenBBox->isChecked()); - -#if QT_VERSION >= 0x040000 - switch (VRinterface->sortMethod->currentIndex()) -#else - switch (VRinterface->sortMethod->currentItem()) -#endif - { - case 0: vparams.setSortMethod(vrender::VRenderParams::NoSorting); break; - case 1: vparams.setSortMethod(vrender::VRenderParams::BSPSort); break; - case 2: vparams.setSortMethod(vrender::VRenderParams::TopologicalSort); break; - case 3: vparams.setSortMethod(vrender::VRenderParams::AdvancedTopologicalSort); break; - default: - qWarning("VRenderInterface::saveVectorialSnapshot: Unknown SortMethod"); - } - - vparams.setProgressFunction(&ProgressDialog::updateProgress); - ProgressDialog::showProgressDialog(widget); - widget->makeCurrent(); - widget->raise(); - vrender::VectorialRender(drawVectorial, (void*) widget, vparams); - ProgressDialog::hideProgressDialog(); -#if QT_VERSION < 0x030000 - widget->setCursor(Qt::arrowCursor); -#else - widget->setCursor(QCursor(Qt::ArrowCursor)); -#endif - // Should return vparams.error(), but this is currently not set. - return 0; + // Configure interface according to selected snapshotFormat + if (snapshotFormat == "XFIG") + { + VRinterface->tightenBBox->setEnabled(false); + VRinterface->colorBackground->setEnabled(false); + } + else + { + VRinterface->tightenBBox->setEnabled(true); + VRinterface->colorBackground->setEnabled(true); + } + + if (VRinterface->exec() == QDialog::Rejected) + return -1; + + vrender::VRenderParams vparams; + vparams.setFilename(fileName); + + if (snapshotFormat == "EPS") vparams.setFormat(vrender::VRenderParams::EPS); + if (snapshotFormat == "PS") vparams.setFormat(vrender::VRenderParams::PS); + if (snapshotFormat == "XFIG") vparams.setFormat(vrender::VRenderParams::XFIG); + + vparams.setOption(vrender::VRenderParams::CullHiddenFaces, !(VRinterface->includeHidden->isChecked())); + vparams.setOption(vrender::VRenderParams::OptimizeBackFaceCulling, VRinterface->cullBackFaces->isChecked()); + vparams.setOption(vrender::VRenderParams::RenderBlackAndWhite, VRinterface->blackAndWhite->isChecked()); + vparams.setOption(vrender::VRenderParams::AddBackground, VRinterface->colorBackground->isChecked()); + vparams.setOption(vrender::VRenderParams::TightenBoundingBox, VRinterface->tightenBBox->isChecked()); + + switch (VRinterface->sortMethod->currentIndex()) + { + case 0: vparams.setSortMethod(vrender::VRenderParams::NoSorting); break; + case 1: vparams.setSortMethod(vrender::VRenderParams::BSPSort); break; + case 2: vparams.setSortMethod(vrender::VRenderParams::TopologicalSort); break; + case 3: vparams.setSortMethod(vrender::VRenderParams::AdvancedTopologicalSort); break; + default: + qWarning("VRenderInterface::saveVectorialSnapshot: Unknown SortMethod"); + } + + vparams.setProgressFunction(&ProgressDialog::updateProgress); + ProgressDialog::showProgressDialog(widget); + widget->makeCurrent(); + widget->raise(); + vrender::VectorialRender(drawVectorial, (void*) widget, vparams); + ProgressDialog::hideProgressDialog(); + widget->setCursor(QCursor(Qt::ArrowCursor)); + + // Should return vparams.error(), but this is currently not set. + return 0; } #endif // NO_VECTORIAL_RENDER -#if QT_VERSION >= 0x040000 class ImageInterface: public QDialog, public Ui::ImageInterface { - public: ImageInterface(QWidget *parent) : QDialog(parent) { setupUi(this); } +public: ImageInterface(QWidget *parent) : QDialog(parent) { setupUi(this); } }; -#endif // Pops-up an image settings dialog box and save to fileName. // Returns false in case of problem. bool QGLViewer::saveImageSnapshot(const QString& fileName) { - static ImageInterface* imageInterface = NULL; + static ImageInterface* imageInterface = NULL; - if (!imageInterface) -#if QT_VERSION >= 0x030000 - imageInterface = new ImageInterface(this); -#else - imageInterface = new ImageInterface(this, "", true); // Make the dialog modal -#endif + if (!imageInterface) + imageInterface = new ImageInterface(this); - // 1 means never set : use current window size as default - if ((imageInterface->imgWidth->value() == 1) && (imageInterface->imgHeight->value() == 1)) - { - imageInterface->imgWidth->setValue(width()); - imageInterface->imgHeight->setValue(height()); - } - - imageInterface->imgQuality->setValue(snapshotQuality()); - - if (imageInterface->exec() == QDialog::Rejected) - return true; - - // Hide closed dialog - qApp->processEvents(); - - setSnapshotQuality(imageInterface->imgQuality->value()); - - QColor previousBGColor = backgroundColor(); - if (imageInterface->whiteBackground->isChecked()) - setBackgroundColor(Qt::white); - - QSize finalSize(imageInterface->imgWidth->value(), imageInterface->imgHeight->value()); - - double oversampling = imageInterface->oversampling->value(); - QSize subSize(int(this->width()/oversampling), int(this->height()/oversampling)); - - double aspectRatio = width() / static_cast(height()); - double newAspectRatio = finalSize.width() / static_cast(finalSize.height()); - - double zNear = camera()->zNear(); - double zFar = camera()->zFar(); - - double xMin, yMin; - bool expand = imageInterface->expandFrustum->isChecked(); - if (camera()->type() == qglviewer::Camera::PERSPECTIVE) - if ((expand && (newAspectRatio>aspectRatio)) || (!expand && (newAspectRatiofieldOfView() / 2.0); - xMin = newAspectRatio * yMin; - } - else - { - xMin = zNear * tan(camera()->fieldOfView() / 2.0) * aspectRatio; - yMin = xMin / newAspectRatio; - } - else - { - camera()->getOrthoWidthHeight(xMin, yMin); - if ((expand && (newAspectRatio>aspectRatio)) || (!expand && (newAspectRatio= 0x040000 - QImage image(finalSize.width(), finalSize.height(), QImage::Format_ARGB32); -#else - QImage image(finalSize.width(), finalSize.height(), 32); -#endif + imageInterface->imgWidth->setValue(width()); + imageInterface->imgHeight->setValue(height()); - if (image.isNull()) - { - QMessageBox::warning(this, "Image saving error", - "Unable to create resulting image", - QMessageBox::Ok, QMessageBox::NoButton); - return false; - } - - // ProgressDialog disabled since it interfers with the screen grabing mecanism on some platforms. Too bad. - // ProgressDialog::showProgressDialog(this); - - double scaleX = subSize.width() / static_cast(finalSize.width()); - double scaleY = subSize.height() / static_cast(finalSize.height()); - - double deltaX = 2.0 * xMin * scaleX; - double deltaY = 2.0 * yMin * scaleY; - - int nbX = finalSize.width() / subSize.width(); - int nbY = finalSize.height() / subSize.height(); - - // Extra subimage on the right/bottom border(s) if needed - if (nbX * subSize.width() < finalSize.width()) - nbX++; - if (nbY * subSize.height() < finalSize.height()) - nbY++; - - makeCurrent(); - - // tileRegion_ is used by startScreenCoordinatesSystem to appropriately set the local - // coordinate system when tiling - tileRegion_ = new TileRegion(); - double tileXMin, tileWidth, tileYMin, tileHeight; - if ((expand && (newAspectRatio>aspectRatio)) || (!expand && (newAspectRatiotextScale = 1.0 / scaleY; - } - else - { - double tileTotalHeight = width() / newAspectRatio; - tileYMin = (height() - tileTotalHeight) / 2.0; - tileHeight = tileTotalHeight * scaleY; - tileXMin = 0.0; - tileWidth = width() * scaleX; - tileRegion_->textScale = 1.0 / scaleX; - } - - int count=0; - for (int i=0; iimgQuality->setValue(snapshotQuality()); + + if (imageInterface->exec() == QDialog::Rejected) + return true; + + // Hide closed dialog + qApp->processEvents(); + + setSnapshotQuality(imageInterface->imgQuality->value()); + + QColor previousBGColor = backgroundColor(); + if (imageInterface->whiteBackground->isChecked()) + setBackgroundColor(Qt::white); + + QSize finalSize(imageInterface->imgWidth->value(), imageInterface->imgHeight->value()); + + qreal oversampling = imageInterface->oversampling->value(); + QSize subSize(int(this->width()/oversampling), int(this->height()/oversampling)); + + qreal aspectRatio = width() / static_cast(height()); + qreal newAspectRatio = finalSize.width() / static_cast(finalSize.height()); + + qreal zNear = camera()->zNear(); + qreal zFar = camera()->zFar(); + + qreal xMin, yMin; + bool expand = imageInterface->expandFrustum->isChecked(); if (camera()->type() == qglviewer::Camera::PERSPECTIVE) - glFrustum(-xMin + i*deltaX, -xMin + (i+1)*deltaX, yMin - (j+1)*deltaY, yMin - j*deltaY, zNear, zFar); + if ((expand && (newAspectRatio>aspectRatio)) || (!expand && (newAspectRatiofieldOfView() / 2.0); + xMin = newAspectRatio * yMin; + } + else + { + xMin = zNear * tan(camera()->fieldOfView() / 2.0) * aspectRatio; + yMin = xMin / newAspectRatio; + } else - glOrtho(-xMin + i*deltaX, -xMin + (i+1)*deltaX, yMin - (j+1)*deltaY, yMin - j*deltaY, zNear, zFar); - glMatrixMode(GL_MODELVIEW); + { + camera()->getOrthoWidthHeight(xMin, yMin); + if ((expand && (newAspectRatio>aspectRatio)) || (!expand && (newAspectRatioxMin = tileXMin + i * tileWidth; - tileRegion_->xMax = tileXMin + (i+1) * tileWidth; - tileRegion_->yMin = tileYMin + j * tileHeight; - tileRegion_->yMax = tileYMin + (j+1) * tileHeight; + QImage image(finalSize.width(), finalSize.height(), QImage::Format_ARGB32); - draw(); - postDraw(); + if (image.isNull()) + { + QMessageBox::warning(this, "Image saving error", + "Unable to create resulting image", + QMessageBox::Ok, QMessageBox::NoButton); + return false; + } - // ProgressDialog::hideProgressDialog(); - // qApp->processEvents(); + // ProgressDialog disabled since it interfers with the screen grabing mecanism on some platforms. Too bad. + // ProgressDialog::showProgressDialog(this); - QImage snapshot = grabFrameBuffer(true); + qreal scaleX = subSize.width() / static_cast(finalSize.width()); + qreal scaleY = subSize.height() / static_cast(finalSize.height()); - // ProgressDialog::showProgressDialog(this); - // ProgressDialog::updateProgress(count / (float)(nbX*nbY), - // "Generating image ["+QString::number(count)+"/"+QString::number(nbX*nbY)+"]"); - // qApp->processEvents(); - -#if QT_VERSION >= 0x040000 - QImage subImage = snapshot.scaled(subSize, Qt::IgnoreAspectRatio, Qt::SmoothTransformation); -#else -# if QT_VERSION >= 0x030000 - QImage subImage = snapshot.scale(subSize, QImage::ScaleFree); -# else - QImage subImage = snapshot.smoothScale(subSize.width(), subSize.height()); -# endif -#endif + qreal deltaX = 2.0 * xMin * scaleX; + qreal deltaY = 2.0 * yMin * scaleY; - // Copy subImage in image - for (int ii=0; ii= 0x040000 - bool saveOK = image.save(fileName, snapshotFormat().toLatin1().constData(), snapshotQuality()); -#else - bool saveOK = image.save(fileName, snapshotFormat(), snapshotQuality()); -#endif + int nbX = finalSize.width() / subSize.width(); + int nbY = finalSize.height() / subSize.height(); - // ProgressDialog::hideProgressDialog(); + // Extra subimage on the right/bottom border(s) if needed + if (nbX * subSize.width() < finalSize.width()) + nbX++; + if (nbY * subSize.height() < finalSize.height()) + nbY++; - // #if QT_VERSION < 0x030000 - // setCursor(Qt::arrowCursor); - // #else - // setCursor(QCursor(Qt::ArrowCursor)); - // #endif + makeCurrent(); - delete tileRegion_; - tileRegion_ = NULL; + // tileRegion_ is used by startScreenCoordinatesSystem to appropriately set the local + // coordinate system when tiling + tileRegion_ = new TileRegion(); + qreal tileXMin, tileWidth, tileYMin, tileHeight; + if ((expand && (newAspectRatio>aspectRatio)) || (!expand && (newAspectRatiotextScale = 1.0 / scaleY; + } + else + { + qreal tileTotalHeight = width() / newAspectRatio; + tileYMin = (height() - tileTotalHeight) / 2.0; + tileHeight = tileTotalHeight * scaleY; + tileXMin = 0.0; + tileWidth = width() * scaleX; + tileRegion_->textScale = 1.0 / scaleX; + } + + int count=0; + for (int i=0; itype() == qglviewer::Camera::PERSPECTIVE) + glFrustum(-xMin + i*deltaX, -xMin + (i+1)*deltaX, yMin - (j+1)*deltaY, yMin - j*deltaY, zNear, zFar); + else + glOrtho(-xMin + i*deltaX, -xMin + (i+1)*deltaX, yMin - (j+1)*deltaY, yMin - j*deltaY, zNear, zFar); + glMatrixMode(GL_MODELVIEW); + + tileRegion_->xMin = tileXMin + i * tileWidth; + tileRegion_->xMax = tileXMin + (i+1) * tileWidth; + tileRegion_->yMin = tileYMin + j * tileHeight; + tileRegion_->yMax = tileYMin + (j+1) * tileHeight; + + draw(); + postDraw(); + + // ProgressDialog::hideProgressDialog(); + // qApp->processEvents(); + + QImage snapshot = grabFrameBuffer(true); + + // ProgressDialog::showProgressDialog(this); + // ProgressDialog::updateProgress(count / (qreal)(nbX*nbY), + // "Generating image ["+QString::number(count)+"/"+QString::number(nbX*nbY)+"]"); + // qApp->processEvents(); + + QImage subImage = snapshot.scaled(subSize, Qt::IgnoreAspectRatio, Qt::SmoothTransformation); + + // Copy subImage in image + for (int ii=0; iiwhiteBackground->isChecked()) - setBackgroundColor(previousBGColor); + // ProgressDialog::hideProgressDialog(); + // setCursor(QCursor(Qt::ArrowCursor)); + + delete tileRegion_; + tileRegion_ = NULL; + + if (imageInterface->whiteBackground->isChecked()) + setBackgroundColor(previousBGColor); - return saveOK; + return saveOK; } @@ -617,11 +513,11 @@ bool QGLViewer::saveImageSnapshot(const QString& fileName) { const int nbImages = 36; for (int i=0; isetOrientation(2.0*M_PI/nbImages, 0.0); // Theta-Phi orientation - showEntireScene(); - updateGL(); // calls draw(), which emits drawFinished(), which calls saveSnapshot() - } + { + camera()->setOrientation(2.0*M_PI/nbImages, 0.0); // Theta-Phi orientation + showEntireScene(); + update(); // calls draw(), which emits drawFinished(), which calls saveSnapshot() + } } \endcode @@ -640,108 +536,72 @@ bool QGLViewer::saveImageSnapshot(const QString& fileName) other windows by this method. */ void QGLViewer::saveSnapshot(bool automatic, bool overwrite) { - // Ask for file name - if (snapshotFileName().isEmpty() || !automatic) - { - QString fileName; -#if QT_VERSION < 0x030000 - if (openSnapshotFormatDialog()) - fileName = QFileDialog::getSaveFileName(snapshotFileName(), FDFormatString[snapshotFormat()]+";;All files (*.*)", this, "Save dialog"); - else - return; -#else - QString selectedFormat = FDFormatString[snapshotFormat()]; -# if QT_VERSION >= 0x040000 - fileName = QFileDialog::getSaveFileName(this, "Choose a file name to save under", snapshotFileName(), formats, &selectedFormat, - overwrite?QFileDialog::DontConfirmOverwrite:QFlag(0)); -# else - fileName = QFileDialog::getSaveFileName(snapshotFileName(), formats, this, - "Save Snapshot dialog", "Choose a file name to save under", &selectedFormat); -# endif - setSnapshotFormat(Qtformat[selectedFormat]); -#endif + // Ask for file name + if (snapshotFileName().isEmpty() || !automatic) + { + QString fileName; + QString selectedFormat = FDFormatString[snapshotFormat()]; + fileName = QFileDialog::getSaveFileName(this, "Choose a file name to save under", snapshotFileName(), formats, &selectedFormat, + overwrite?QFileDialog::DontConfirmOverwrite:QFlags(0)); + setSnapshotFormat(Qtformat[selectedFormat]); + + if (checkFileName(fileName, this, snapshotFormat())) + setSnapshotFileName(fileName); + else + return; + } - if (checkFileName(fileName, this, snapshotFormat())) - setSnapshotFileName(fileName); - else - return; - } - - QFileInfo fileInfo(snapshotFileName()); - - if ((automatic) && (snapshotCounter() >= 0)) - { - // In automatic mode, names have a number appended - const QString baseName = fileInfo.baseName(); - QString count; - count.sprintf("%.04d", snapshotCounter_++); - QString suffix; -#if QT_VERSION >= 0x040000 - suffix = fileInfo.suffix(); - if (suffix.isEmpty()) - suffix = extension[snapshotFormat()]; - fileInfo.setFile(fileInfo.absolutePath()+ '/' + baseName + '-' + count + '.' + suffix); -#else - suffix = fileInfo.extension(); - if (suffix.isEmpty()) - suffix = extension[snapshotFormat()]; - fileInfo.setFile(fileInfo.dirPath()+ '/' + baseName + '-' + count + '.' + suffix); -#endif + QFileInfo fileInfo(snapshotFileName()); - if (!overwrite) - while (fileInfo.exists()) - { - count.sprintf("%.04d", snapshotCounter_++); -#if QT_VERSION >= 0x040000 - fileInfo.setFile(fileInfo.absolutePath() + '/' +baseName + '-' + count + '.' + fileInfo.suffix()); -#else - fileInfo.setFile(fileInfo.dirPath() + '/' + baseName + '-' + count + '.' + fileInfo.extension()); -#endif - } - } - -#if QT_VERSION < 0x040000 - if ((fileInfo.exists()) && (!overwrite) && - (QMessageBox::warning(this,"Overwrite file ?", - "File "+fileInfo.fileName()+" already exists.\nOverwrite ?", - QMessageBox::Yes, - QMessageBox::Cancel) == QMessageBox::Cancel)) - return; -#endif - - bool saveOK; -#ifndef NO_VECTORIAL_RENDER - if ( (snapshotFormat() == "EPS") || (snapshotFormat() == "PS") || (snapshotFormat() == "XFIG") ) - // Vectorial snapshot. -1 means cancel, 0 is ok, >0 (should be) an error - saveOK = (saveVectorialSnapshot(fileInfo.filePath(), this, snapshotFormat()) <= 0); - else -#endif - if (automatic) + if ((automatic) && (snapshotCounter() >= 0)) { - QImage snapshot = frameBufferSnapshot(); -#if QT_VERSION >= 0x040000 - saveOK = snapshot.save(fileInfo.filePath(), snapshotFormat().toLatin1().constData(), snapshotQuality()); -#else - saveOK = snapshot.save(fileInfo.filePath(), snapshotFormat(), snapshotQuality()); -#endif + // In automatic mode, names have a number appended + const QString baseName = fileInfo.baseName(); + QString count; + count.sprintf("%.04d", snapshotCounter_++); + QString suffix; + suffix = fileInfo.suffix(); + if (suffix.isEmpty()) + suffix = extension[snapshotFormat()]; + fileInfo.setFile(fileInfo.absolutePath()+ '/' + baseName + '-' + count + '.' + suffix); + + if (!overwrite) + while (fileInfo.exists()) + { + count.sprintf("%.04d", snapshotCounter_++); + fileInfo.setFile(fileInfo.absolutePath() + '/' +baseName + '-' + count + '.' + fileInfo.suffix()); + } } + + bool saveOK; +#ifndef NO_VECTORIAL_RENDER + if ( (snapshotFormat() == "EPS") || (snapshotFormat() == "PS") || (snapshotFormat() == "XFIG") ) + // Vectorial snapshot. -1 means cancel, 0 is ok, >0 (should be) an error + saveOK = (saveVectorialSnapshot(fileInfo.filePath(), this, snapshotFormat()) <= 0); else - saveOK = saveImageSnapshot(fileInfo.filePath()); +#endif + if (automatic) + { + QImage snapshot = frameBufferSnapshot(); + saveOK = snapshot.save(fileInfo.filePath(), snapshotFormat().toLatin1().constData(), snapshotQuality()); + } + else + saveOK = saveImageSnapshot(fileInfo.filePath()); - if (!saveOK) - QMessageBox::warning(this, "Snapshot problem", "Unable to save snapshot in\n"+fileInfo.filePath()); + if (!saveOK) + QMessageBox::warning(this, "Snapshot problem", "Unable to save snapshot in\n"+fileInfo.filePath()); } QImage QGLViewer::frameBufferSnapshot() { - // Viewer must be on top of other windows. - makeCurrent(); - raise(); - // Hack: Qt has problems if the frame buffer is grabbed after QFileDialog is displayed. - // We grab the frame buffer before, even if it might be not necessary (vectorial rendering). - // The problem could not be reproduced on a simple example to submit a Qt bug. - // However, only grabs the backgroundImage in the eponym example. May come from the driver. - return grabFrameBuffer(true); + // Viewer must be on top of other windows. + makeCurrent(); + raise(); + // Hack: Qt has problems if the frame buffer is grabbed after QFileDialog is displayed. + // We grab the frame buffer before, even if it might be not necessary (vectorial rendering). + // The problem could not be reproduced on a simple example to submit a Qt bug. + // However, only grabs the backgroundImage in the eponym example. May come from the driver. + return grabFrameBuffer(true); } /*! Same as saveSnapshot(), except that it uses \p fileName instead of snapshotFileName(). @@ -757,13 +617,13 @@ QImage QGLViewer::frameBufferSnapshot() prevent this. */ void QGLViewer::saveSnapshot(const QString& fileName, bool overwrite) { - const QString previousName = snapshotFileName(); - const int previousCounter = snapshotCounter(); - setSnapshotFileName(fileName); - setSnapshotCounter(-1); - saveSnapshot(true, overwrite); - setSnapshotFileName(previousName); - setSnapshotCounter(previousCounter); + const QString previousName = snapshotFileName(); + const int previousCounter = snapshotCounter(); + setSnapshotFileName(fileName); + setSnapshotCounter(-1); + saveSnapshot(true, overwrite); + setSnapshotFileName(previousName); + setSnapshotCounter(previousCounter); } /*! Takes a snapshot of the current display and pastes it to the clipboard. @@ -773,66 +633,6 @@ This action is activated by the KeyboardAction::SNAPSHOT_TO_CLIPBOARD enum, bind void QGLViewer::snapshotToClipboard() { QClipboard *cb = QApplication::clipboard(); - cb->setImage(frameBufferSnapshot()); -} - -#if QT_VERSION < 0x030000 -// This code is largely inspired from Qt's method available in version 3 -// Copyright Trolltech AS -QImage QGLViewer::grabFrameBuffer(bool withAlpha) -{ - makeCurrent(); - QImage res; - int w = width(); - int h = height(); - if (format().rgba()) - { - res = QImage(w, h, 32); - glReadPixels(0, 0, w, h, GL_RGBA, GL_UNSIGNED_BYTE, res.bits()); - if (QImage::systemByteOrder() == QImage::BigEndian) - { - // OpenGL gives RGBA; Qt wants ARGB - uint *p = (uint*)res.bits(); - uint *end = p + w*h; - if (withAlpha && format().alpha()) - { - while (p < end) - { - uint a = *p << 24; - *p = (*p >> 8) | a; - p++; - } - } - else - { - while (p < end) - *p++ >>= 8; - } - } - else - { - // OpenGL gives ABGR (i.e. RGBA backwards); Qt wants ARGB - res = res.swapRGB(); - } - res.setAlphaBuffer(withAlpha && format().alpha()); - } - else - { -#if defined (Q_OS_WIN) || defined (Q_WS_WIN) - res = QImage(w, h, 8); - glReadPixels(0, 0, w, h, GL_COLOR_INDEX, GL_UNSIGNED_BYTE, res.bits()); - //int palSize = 0; - //const QRgb* pal = QColor::palette(&palSize); - //if (pal && palSize) - //{ - // res.setNumColors(palSize); - // for (int i = 0; i < palSize; i++) - // res.setColor(i, pal[i]); - //} -#endif - } - - return res.mirror(); + cb->setImage(frameBufferSnapshot()); } -#endif // QT_VERSION < 0x030000 diff --git a/octovis/src/extern/QGLViewer/vec.cpp b/octovis/src/extern/QGLViewer/vec.cpp index 790c278b..669d6f71 100644 --- a/octovis/src/extern/QGLViewer/vec.cpp +++ b/octovis/src/extern/QGLViewer/vec.cpp @@ -1,8 +1,8 @@ /**************************************************************************** - Copyright (C) 2002-2013 Gilles Debunne. All rights reserved. + Copyright (C) 2002-2014 Gilles Debunne. All rights reserved. - This file is part of the QGLViewer library version 2.4.0. + This file is part of the QGLViewer library version 2.6.3. http://www.libqglviewer.com - contact@libqglviewer.com @@ -34,11 +34,11 @@ using namespace std; void Vec::projectOnAxis(const Vec& direction) { #ifndef QT_NO_DEBUG - if (direction.squaredNorm() < 1.0E-10) - qWarning("Vec::projectOnAxis: axis direction is not normalized (norm=%f).", direction.norm()); + if (direction.squaredNorm() < 1.0E-10) + qWarning("Vec::projectOnAxis: axis direction is not normalized (norm=%f).", direction.norm()); #endif - *this = (((*this)*direction) / direction.squaredNorm()) * direction; + *this = (((*this)*direction) / direction.squaredNorm()) * direction; } /*! Projects the Vec on the plane whose normal is \p normal that passes through the origin. @@ -47,25 +47,25 @@ void Vec::projectOnAxis(const Vec& direction) void Vec::projectOnPlane(const Vec& normal) { #ifndef QT_NO_DEBUG - if (normal.squaredNorm() < 1.0E-10) - qWarning("Vec::projectOnPlane: plane normal is not normalized (norm=%f).", normal.norm()); + if (normal.squaredNorm() < 1.0E-10) + qWarning("Vec::projectOnPlane: plane normal is not normalized (norm=%f).", normal.norm()); #endif - *this -= (((*this)*normal) / normal.squaredNorm()) * normal; + *this -= (((*this)*normal) / normal.squaredNorm()) * normal; } /*! Returns a Vec orthogonal to the Vec. Its norm() depends on the Vec, but is zero only for a null Vec. Note that the function that associates an orthogonalVec() to a Vec is not continous. */ Vec Vec::orthogonalVec() const { - // Find smallest component. Keep equal case for null values. - if ((fabs(y) >= 0.9*fabs(x)) && (fabs(z) >= 0.9*fabs(x))) - return Vec(0.0, -z, y); - else - if ((fabs(x) >= 0.9*fabs(y)) && (fabs(z) >= 0.9*fabs(y))) - return Vec(-z, 0.0, x); - else - return Vec(-y, x, 0.0); + // Find smallest component. Keep equal case for null values. + if ((fabs(y) >= 0.9*fabs(x)) && (fabs(z) >= 0.9*fabs(x))) + return Vec(0.0, -z, y); + else + if ((fabs(x) >= 0.9*fabs(y)) && (fabs(z) >= 0.9*fabs(y))) + return Vec(-z, 0.0, x); + else + return Vec(-y, x, 0.0); } /*! Constructs a Vec from a \c QDomElement representing an XML code of the form @@ -77,17 +77,13 @@ value is set to 0.0. See also domElement() and initFromDOMElement(). */ Vec::Vec(const QDomElement& element) { - QStringList attribute; - attribute << "x" << "y" << "z"; -#if QT_VERSION >= 0x040000 - for (int i=0; ioperator[](i) = DomUtils::doubleFromDom(element, attribute[i], 0.0); + this->operator[](i) = DomUtils::qrealFromDom(element, attribute[i], 0.0); #else - v_[i] = DomUtils::doubleFromDom(element, attribute[i], 0.0); + v_[i] = DomUtils::qrealFromDom(element, attribute[i], 0.0); #endif } @@ -127,11 +123,11 @@ Vec::Vec(const QDomElement& element) See also Quaternion::domElement(), Frame::domElement(), Camera::domElement()... */ QDomElement Vec::domElement(const QString& name, QDomDocument& document) const { - QDomElement de = document.createElement(name); - de.setAttribute("x", QString::number(x)); - de.setAttribute("y", QString::number(y)); - de.setAttribute("z", QString::number(z)); - return de; + QDomElement de = document.createElement(name); + de.setAttribute("x", QString::number(x)); + de.setAttribute("y", QString::number(y)); + de.setAttribute("z", QString::number(z)); + return de; } /*! Restores the Vec state from a \c QDomElement created by domElement(). @@ -157,12 +153,12 @@ QDomElement Vec::domElement(const QString& name, QDomDocument& document) const See also the Vec(const QDomElement&) constructor. */ void Vec::initFromDOMElement(const QDomElement& element) { - const Vec v(element); - *this = v; + const Vec v(element); + *this = v; } ostream& operator<<(ostream& o, const Vec& v) { - return o << v.x << '\t' << v.y << '\t' << v.z; + return o << v.x << '\t' << v.y << '\t' << v.z; } diff --git a/octovis/src/extern/QGLViewer/vec.h b/octovis/src/extern/QGLViewer/vec.h index 2e3fb5e1..429ab62a 100644 --- a/octovis/src/extern/QGLViewer/vec.h +++ b/octovis/src/extern/QGLViewer/vec.h @@ -1,8 +1,8 @@ /**************************************************************************** - Copyright (C) 2002-2013 Gilles Debunne. All rights reserved. + Copyright (C) 2002-2014 Gilles Debunne. All rights reserved. - This file is part of the QGLViewer library version 2.4.0. + This file is part of the QGLViewer library version 2.6.3. http://www.libqglviewer.com - contact@libqglviewer.com @@ -26,11 +26,7 @@ #include #include -#if QT_VERSION >= 0x040000 # include -#else -# include -#endif // Included by all files as vec.h is at the end of the include hierarchy #include "config.h" // Specific configuration options. @@ -69,321 +65,321 @@ namespace qglviewer { class QGLVIEWER_EXPORT Vec { - // If your compiler complains the "The class "qglviewer::Vec" has no member "x"." - // Add your architecture Q_OS_XXXX flag (see qglobal.h) in this list. + // If your compiler complains the "The class "qglviewer::Vec" has no member "x"." + // Add your architecture Q_OS_XXXX flag (see qglobal.h) in this list. #if defined (Q_OS_IRIX) || defined (Q_OS_AIX) || defined (Q_OS_HPUX) # define QGLVIEWER_UNION_NOT_SUPPORTED #endif public: - /*! The internal data representation is public. One can use v.x, v.y, v.z. See also operator[](). */ + /*! The internal data representation is public. One can use v.x, v.y, v.z. See also operator[](). */ #if defined (DOXYGEN) || defined (QGLVIEWER_UNION_NOT_SUPPORTED) - double x, y, z; + qreal x, y, z; #else - union - { - struct { double x, y, z; }; - double v_[3]; - }; + union + { + struct { qreal x, y, z; }; + qreal v_[3]; + }; #endif - /*! @name Setting the value */ - //@{ - /*! Default constructor. Value is set to (0,0,0). */ - Vec() : x(0.0), y(0.0), z(0.0) {} + /*! @name Setting the value */ + //@{ + /*! Default constructor. Value is set to (0,0,0). */ + Vec() : x(0.0), y(0.0), z(0.0) {} - /*! Standard constructor with the x, y and z values. */ - Vec(double X, double Y, double Z) : x(X), y(Y), z(Z) {} + /*! Standard constructor with the x, y and z values. */ + Vec(qreal X, qreal Y, qreal Z) : x(X), y(Y), z(Z) {} - /*! Universal explicit converter from any class to Vec. You can use your own vector class everywhere + /*! Universal explicit converter from any class to Vec. You can use your own vector class everywhere a \c const \c Vec& parameter is required, as long as it implements the \c operator[ ]: \code class MyVec { - // ... - double operator[](int i) const { returns x, y or z when i=0, 1 or 2; } + // ... + qreal operator[](int i) const { returns x, y or z when i=0, 1 or 2; } } MyVec v(...); camera()->setPosition(v); \endcode - Note that standard vector types (STL, \c double[3], ...) implement this operator and can hence - be used in place of Vec. See also operator const double*() .*/ - template - explicit Vec(const C& c) : x(c[0]), y(c[1]), z(c[2]) {} - // Should NOT be explicit to prevent conflicts with operator<<. - - // ! Copy constructor - // Vec(const Vec& v) : x(v.x), y(v.y), z(v.z) {} - - /*! Equal operator. */ - Vec& operator=(const Vec& v) - { - x = v.x; y = v.y; z = v.z; - return *this; - } - - /*! Set the current value. May be faster than using operator=() with a temporary Vec(x,y,z). */ - void setValue(double X, double Y, double Z) - { x=X; y=Y; z=Z; } - - // Universal equal operator which allows the use of any type in place of Vec, - // as long as the [] operator is implemented (v[0]=v.x, v[1]=v.y, v[2]=v.z). - // template - // Vec& operator=(const C& c) - // { - // x=c[0]; y=c[1]; z=c[2]; - // return *this; - // } - //@} - - /*! @name Accessing the value */ - //@{ - /*! Bracket operator, with a constant return value. \p i must range in [0..2]. */ - double operator[](int i) const { + Note that standard vector types (STL, \c qreal[3], ...) implement this operator and can hence + be used in place of Vec. See also operator const qreal*() .*/ + template + explicit Vec(const C& c) : x(c[0]), y(c[1]), z(c[2]) {} + // Should NOT be explicit to prevent conflicts with operator<<. + + // ! Copy constructor + // Vec(const Vec& v) : x(v.x), y(v.y), z(v.z) {} + + /*! Equal operator. */ + Vec& operator=(const Vec& v) + { + x = v.x; y = v.y; z = v.z; + return *this; + } + + /*! Set the current value. May be faster than using operator=() with a temporary Vec(x,y,z). */ + void setValue(qreal X, qreal Y, qreal Z) + { x=X; y=Y; z=Z; } + + // Universal equal operator which allows the use of any type in place of Vec, + // as long as the [] operator is implemented (v[0]=v.x, v[1]=v.y, v[2]=v.z). + // template + // Vec& operator=(const C& c) + // { + // x=c[0]; y=c[1]; z=c[2]; + // return *this; + // } + //@} + + /*! @name Accessing the value */ + //@{ + /*! Bracket operator, with a constant return value. \p i must range in [0..2]. */ + qreal operator[](int i) const { #ifdef QGLVIEWER_UNION_NOT_SUPPORTED - return (&x)[i]; + return (&x)[i]; #else - return v_[i]; + return v_[i]; #endif - } + } - /*! Bracket operator returning an l-value. \p i must range in [0..2]. */ - double& operator[](int i) { + /*! Bracket operator returning an l-value. \p i must range in [0..2]. */ + qreal& operator[](int i) { #ifdef QGLVIEWER_UNION_NOT_SUPPORTED - return (&x)[i]; + return (&x)[i]; #else - return v_[i]; + return v_[i]; #endif - } + } #ifndef DOXYGEN - /*! This method is deprecated since version 2.0. Use operator const double* instead. */ - const double* address() const { qWarning("Vec::address() is deprecated, use operator const double* instead."); return operator const double*(); }; + /*! This method is deprecated since version 2.0. Use operator const double* instead. */ + const double* address() const { qWarning("Vec::address() is deprecated, use operator const double* instead."); return operator const double*(); } #endif - /*! Conversion operator returning the memory address of the vector. + /*! Conversion operator returning the memory address of the vector. - Very convenient to pass a Vec pointer as a parameter to OpenGL functions: + Very convenient to pass a Vec pointer as a parameter to \c GLdouble OpenGL functions: \code Vec pos, normal; glNormal3dv(normal); glVertex3dv(pos); \endcode */ - operator const double*() const { + operator const double*() const { #ifdef QGLVIEWER_UNION_NOT_SUPPORTED - return &x; + return &x; #else - return v_; + return v_; #endif - } + } - /*! Non const conversion operator returning the memory address of the vector. + /*! Non const conversion operator returning the memory address of the vector. Useful to pass a Vec to a method that requires and fills a \c double*, as provided by certain libraries. */ - operator double*() { + operator double*() { #ifdef QGLVIEWER_UNION_NOT_SUPPORTED - return &x; + return &x; #else - return v_; + return v_; #endif - } + } - /*! Conversion operator returning the memory address of the vector. + /*! Conversion operator returning the memory address of the vector. - Very convenient to pass a Vec pointer as a parameter to OpenGL functions: + Very convenient to pass a Vec pointer as a \c float parameter to OpenGL functions: \code Vec pos, normal; glNormal3fv(normal); glVertex3fv(pos); \endcode \note The returned float array is a static shared by all \c Vec instances. */ - operator const float*() const { - static float* const result = new float[3]; - result[0] = (float)x; - result[1] = (float)y; - result[2] = (float)z; - return result; - } - //@} - - /*! @name Algebraic computations */ - //@{ - /*! Returns the sum of the two vectors. */ - friend Vec operator+(const Vec &a, const Vec &b) - { - return Vec(a.x+b.x, a.y+b.y, a.z+b.z); - } - - /*! Returns the difference of the two vectors. */ - friend Vec operator-(const Vec &a, const Vec &b) - { - return Vec(a.x-b.x, a.y-b.y, a.z-b.z); - } - - /*! Unary minus operator. */ - friend Vec operator-(const Vec &a) - { - return Vec(-a.x, -a.y, -a.z); - } - - /*! Returns the product of the vector with a scalar. */ - friend Vec operator*(const Vec &a, double k) - { - return Vec(a.x*k, a.y*k, a.z*k); - } - - /*! Returns the product of a scalar with the vector. */ - friend Vec operator*(double k, const Vec &a) - { - return a*k; - } - - /*! Returns the division of the vector with a scalar. + operator const float*() const { + static float* const result = new float[3]; + result[0] = (float)x; + result[1] = (float)y; + result[2] = (float)z; + return result; + } + //@} + + /*! @name Algebraic computations */ + //@{ + /*! Returns the sum of the two vectors. */ + friend Vec operator+(const Vec &a, const Vec &b) + { + return Vec(a.x+b.x, a.y+b.y, a.z+b.z); + } + + /*! Returns the difference of the two vectors. */ + friend Vec operator-(const Vec &a, const Vec &b) + { + return Vec(a.x-b.x, a.y-b.y, a.z-b.z); + } + + /*! Unary minus operator. */ + friend Vec operator-(const Vec &a) + { + return Vec(-a.x, -a.y, -a.z); + } + + /*! Returns the product of the vector with a scalar. */ + friend Vec operator*(const Vec &a, qreal k) + { + return Vec(a.x*k, a.y*k, a.z*k); + } + + /*! Returns the product of a scalar with the vector. */ + friend Vec operator*(qreal k, const Vec &a) + { + return a*k; + } + + /*! Returns the division of the vector with a scalar. Too small \p k values are \e not tested (unless the library was compiled with the "debug" Qt \c CONFIG flag) and may result in \c NaN values. */ - friend Vec operator/(const Vec &a, double k) - { + friend Vec operator/(const Vec &a, qreal k) + { #ifndef QT_NO_DEBUG - if (fabs(k) < 1.0E-10) - qWarning("Vec::operator / : dividing by a null value (%f)", k); + if (fabs(k) < 1.0E-10) + qWarning("Vec::operator / : dividing by a null value (%f)", k); #endif - return Vec(a.x/k, a.y/k, a.z/k); - } - - /*! Returns \c true only when the two vector are not equal (see operator==()). */ - friend bool operator!=(const Vec &a, const Vec &b) - { - return !(a==b); - } - - /*! Returns \c true when the squaredNorm() of the difference vector is lower than 1E-10. */ - friend bool operator==(const Vec &a, const Vec &b) - { - const double epsilon = 1.0E-10f; - return (a-b).squaredNorm() < epsilon; - } - - /*! Adds \p a to the vector. */ - Vec& operator+=(const Vec &a) - { - x += a.x; y += a.y; z += a.z; - return *this; - } - - /*! Subtracts \p a to the vector. */ - Vec& operator-=(const Vec &a) - { - x -= a.x; y -= a.y; z -= a.z; - return *this; - } - - /*! Multiply the vector by a scalar \p k. */ - Vec& operator*=(double k) - { - x *= k; y *= k; z *= k; - return *this; - } - - /*! Divides the vector by a scalar \p k. + return Vec(a.x/k, a.y/k, a.z/k); + } + + /*! Returns \c true only when the two vector are not equal (see operator==()). */ + friend bool operator!=(const Vec &a, const Vec &b) + { + return !(a==b); + } + + /*! Returns \c true when the squaredNorm() of the difference vector is lower than 1E-10. */ + friend bool operator==(const Vec &a, const Vec &b) + { + const qreal epsilon = 1.0E-10; + return (a-b).squaredNorm() < epsilon; + } + + /*! Adds \p a to the vector. */ + Vec& operator+=(const Vec &a) + { + x += a.x; y += a.y; z += a.z; + return *this; + } + + /*! Subtracts \p a to the vector. */ + Vec& operator-=(const Vec &a) + { + x -= a.x; y -= a.y; z -= a.z; + return *this; + } + + /*! Multiply the vector by a scalar \p k. */ + Vec& operator*=(qreal k) + { + x *= k; y *= k; z *= k; + return *this; + } + + /*! Divides the vector by a scalar \p k. An absolute \p k value lower than 1E-10 will print a warning if the library was compiled with the "debug" Qt \c CONFIG flag. Otherwise, no test is performed for efficiency reasons. */ - Vec& operator/=(double k) - { + Vec& operator/=(qreal k) + { #ifndef QT_NO_DEBUG - if (fabs(k)<1.0E-10) - qWarning("Vec::operator /= : dividing by a null value (%f)", k); + if (fabs(k)<1.0E-10) + qWarning("Vec::operator /= : dividing by a null value (%f)", k); #endif - x /= k; y /= k; z /= k; - return *this; - } - - /*! Dot product of the two Vec. */ - friend double operator*(const Vec &a, const Vec &b) - { - return a.x*b.x + a.y*b.y + a.z*b.z; - } - - /*! Cross product of the two vectors. Same as cross(). */ - friend Vec operator^(const Vec &a, const Vec &b) - { - return cross(a,b); - } - - /*! Cross product of the two Vec. Mind the order ! */ - friend Vec cross(const Vec &a, const Vec &b) - { - return Vec(a.y*b.z - a.z*b.y, - a.z*b.x - a.x*b.z, - a.x*b.y - a.y*b.x); - } - - Vec orthogonalVec() const; - //@} - - /*! @name Norm of the vector */ - //@{ + x /= k; y /= k; z /= k; + return *this; + } + + /*! Dot product of the two Vec. */ + friend qreal operator*(const Vec &a, const Vec &b) + { + return a.x*b.x + a.y*b.y + a.z*b.z; + } + + /*! Cross product of the two vectors. Same as cross(). */ + friend Vec operator^(const Vec &a, const Vec &b) + { + return cross(a,b); + } + + /*! Cross product of the two Vec. Mind the order ! */ + friend Vec cross(const Vec &a, const Vec &b) + { + return Vec(a.y*b.z - a.z*b.y, + a.z*b.x - a.x*b.z, + a.x*b.y - a.y*b.x); + } + + Vec orthogonalVec() const; + //@} + + /*! @name Norm of the vector */ + //@{ #ifndef DOXYGEN - /*! This method is deprecated since version 2.0. Use squaredNorm() instead. */ - double sqNorm() const { return x*x + y*y + z*z; } + /*! This method is deprecated since version 2.0. Use squaredNorm() instead. */ + qreal sqNorm() const { return x*x + y*y + z*z; } #endif - /*! Returns the \e squared norm of the Vec. */ - double squaredNorm() const { return x*x + y*y + z*z; } + /*! Returns the \e squared norm of the Vec. */ + qreal squaredNorm() const { return x*x + y*y + z*z; } - /*! Returns the norm of the vector. */ - double norm() const { return sqrt(x*x + y*y + z*z); } + /*! Returns the norm of the vector. */ + qreal norm() const { return sqrt(x*x + y*y + z*z); } - /*! Normalizes the Vec and returns its original norm. + /*! Normalizes the Vec and returns its original norm. Normalizing a null vector will result in \c NaN values. */ - double normalize() - { - const double n = norm(); + qreal normalize() + { + const qreal n = norm(); #ifndef QT_NO_DEBUG - if (n < 1.0E-10) - qWarning("Vec::normalize: normalizing a null vector (norm=%f)", n); + if (n < 1.0E-10) + qWarning("Vec::normalize: normalizing a null vector (norm=%f)", n); #endif - *this /= n; - return n; - } - - /*! Returns a unitary (normalized) \e representation of the vector. The original Vec is not modified. */ - Vec unit() const - { - Vec v = *this; - v.normalize(); - return v; - } - //@} - - /*! @name Projection */ - //@{ - void projectOnAxis(const Vec& direction); - void projectOnPlane(const Vec& normal); - //@} - - /*! @name XML representation */ - //@{ - explicit Vec(const QDomElement& element); - QDomElement domElement(const QString& name, QDomDocument& document) const; - void initFromDOMElement(const QDomElement& element); - //@} + *this /= n; + return n; + } + + /*! Returns a unitary (normalized) \e representation of the vector. The original Vec is not modified. */ + Vec unit() const + { + Vec v = *this; + v.normalize(); + return v; + } + //@} + + /*! @name Projection */ + //@{ + void projectOnAxis(const Vec& direction); + void projectOnPlane(const Vec& normal); + //@} + + /*! @name XML representation */ + //@{ + explicit Vec(const QDomElement& element); + QDomElement domElement(const QString& name, QDomDocument& document) const; + void initFromDOMElement(const QDomElement& element); + //@} #ifdef DOXYGEN - /*! @name Output stream */ - //@{ - /*! Output stream operator. Enables debugging code like: + /*! @name Output stream */ + //@{ + /*! Output stream operator. Enables debugging code like: \code Vec pos(...); cout << "Position=" << pos << endl; \endcode */ - std::ostream& operator<<(std::ostream& o, const qglviewer::Vec&); - //@} + std::ostream& operator<<(std::ostream& o, const qglviewer::Vec&); + //@} #endif }; From 0d174e9eed54c24de0b4334ee9df8e475501214b Mon Sep 17 00:00:00 2001 From: Armin Hornung Date: Wed, 20 Apr 2016 21:36:17 +0200 Subject: [PATCH 28/28] Version 1.8.0 release --- dynamicEDT3D/CMakeLists.txt | 4 ++-- dynamicEDT3D/package.xml | 2 +- octomap/AUTHORS.txt | 5 ++++- octomap/CHANGELOG.txt | 28 ++++++++++++++++++++++++++++ octomap/CMakeLists.txt | 4 ++-- octomap/package.xml | 2 +- octovis/CMakeLists.txt | 4 ++-- octovis/package.xml | 2 +- 8 files changed, 41 insertions(+), 10 deletions(-) diff --git a/dynamicEDT3D/CMakeLists.txt b/dynamicEDT3D/CMakeLists.txt index 23b212a0..195a8704 100644 --- a/dynamicEDT3D/CMakeLists.txt +++ b/dynamicEDT3D/CMakeLists.txt @@ -5,8 +5,8 @@ ENABLE_TESTING() # version (e.g. for packaging) set(DYNAMICEDT3D_MAJOR_VERSION 1) -set(DYNAMICEDT3D_MINOR_VERSION 7) -set(DYNAMICEDT3D_PATCH_VERSION 2) +set(DYNAMICEDT3D_MINOR_VERSION 8) +set(DYNAMICEDT3D_PATCH_VERSION 0) set(DYNAMICEDT3D_VERSION ${DYNAMICEDT3D_MAJOR_VERSION}.${DYNAMICEDT3D_MINOR_VERSION}.${DYNAMICEDT3D_PATCH_VERSION}) set(DYNAMICEDT3D_SOVERSION ${DYNAMICEDT3D_MAJOR_VERSION}.${DYNAMICEDT3D_MINOR_VERSION}) diff --git a/dynamicEDT3D/package.xml b/dynamicEDT3D/package.xml index 5f96c240..a25cd01f 100644 --- a/dynamicEDT3D/package.xml +++ b/dynamicEDT3D/package.xml @@ -1,6 +1,6 @@ dynamic_edt_3d - 1.7.2 + 1.8.0 The dynamicEDT3D library implements an inrementally updatable Euclidean distance transform (EDT) in 3D. It comes with a wrapper to use the OctoMap 3D representation and hooks into the change detection of the OctoMap library to propagate changes to the EDT. Christoph Sprunk diff --git a/octomap/AUTHORS.txt b/octomap/AUTHORS.txt index 30560c84..bebd91dc 100644 --- a/octomap/AUTHORS.txt +++ b/octomap/AUTHORS.txt @@ -9,4 +9,7 @@ Further contributors: * R. Bogdan Rusu, Willow Garage Inc. * C. Dornhege, University of Freiburg * F-M. de Rainville, Universite Laval Quebec -* B. Jensen, TU Munich \ No newline at end of file +* B. Jensen, TU Munich +* A. Ecins, University of Maryland +* C. Brew +* F. Boniardi, University of Freiburg \ No newline at end of file diff --git a/octomap/CHANGELOG.txt b/octomap/CHANGELOG.txt index 9e42cbd6..8775f7a5 100644 --- a/octomap/CHANGELOG.txt +++ b/octomap/CHANGELOG.txt @@ -1,3 +1,31 @@ +v1.8.0: 2016-04-20 +================== +- Fixed #98: The tree structure in memory is now maintained in OcTreeBaseImpl to + enable safely deriving custom node classes. The following functions were + moved from OcTreeDataNode into OcTreeBaseImpl: + createChild(...) -> OcTreeBaseImpl::createNodeChild(...) + getChild(...) -> OcTreeBaseImpl::getNodeChild(...) + expandNode() -> OcTreeBaseImpl::expandNode(...) + pruneNode() -> OcTreeBaseImpl::pruneNode(...) + hasChildren() -> OcTreeBaseImpl::nodeHasChildren(...) + childExists(...) -> OcTreeBaseImpl::nodeChildExist(...) + collapsible() -> OcTreeBaseImpl::isNodeCollapsible(...) + If you use custom derived node classes, you need to adjust your code to the + new API (have a look at ColorOcTree.h as an example). In particular, you + should no longer use the above node member functions in your nodes. +- Extended unit tests for the new memory management +- Added valgrind memcheck suppression file with known ("wanted") leaks due to + StaticMemberInitializer. +- Replaced `unsigned short int` for key values with octomap::key_type + (=uint16_t) and unsigned char with uint8_t in API. +- Cleaned up OcTreeKey and KeyRay API (used internally) +- Reduced unneeded memory for StaticMemberInitializer +- Cleaned up const refs to primitive types in ColorOcTree interface +- Removed deprecated insertScan functions (replaced by insertPointCloud) +- Removed no longer used ROS logging macros and unmaintained OcTreeLUT, + OcTreeBaseSE classes +- octovis: Internal version of libQGLViewer updated to 2.6.3 + v1.7.2: 2016-03-26 ================== - BBX iterators fixed for empty trees (point3d version) diff --git a/octomap/CMakeLists.txt b/octomap/CMakeLists.txt index 7cf1bee7..fcafca18 100644 --- a/octomap/CMakeLists.txt +++ b/octomap/CMakeLists.txt @@ -5,8 +5,8 @@ ENABLE_TESTING() # version (e.g. for packaging) set(OCTOMAP_MAJOR_VERSION 1) -set(OCTOMAP_MINOR_VERSION 7) -set(OCTOMAP_PATCH_VERSION 2) +set(OCTOMAP_MINOR_VERSION 8) +set(OCTOMAP_PATCH_VERSION 0) set(OCTOMAP_VERSION ${OCTOMAP_MAJOR_VERSION}.${OCTOMAP_MINOR_VERSION}.${OCTOMAP_PATCH_VERSION}) set(OCTOMAP_SOVERSION ${OCTOMAP_MAJOR_VERSION}.${OCTOMAP_MINOR_VERSION}) if(COMMAND cmake_policy) diff --git a/octomap/package.xml b/octomap/package.xml index f09af15b..ed2282c6 100644 --- a/octomap/package.xml +++ b/octomap/package.xml @@ -1,6 +1,6 @@ octomap - 1.7.2 + 1.8.0 The OctoMap library implements a 3D occupancy grid mapping approach, providing data structures and mapping algorithms in C++. The map implementation is based on an octree. See http://octomap.github.io for details. diff --git a/octovis/CMakeLists.txt b/octovis/CMakeLists.txt index 46cf8469..87fb9a51 100644 --- a/octovis/CMakeLists.txt +++ b/octovis/CMakeLists.txt @@ -3,8 +3,8 @@ PROJECT( octovis ) # # version (e.g. for packaging) set(OCTOVIS_MAJOR_VERSION 1) -set(OCTOVIS_MINOR_VERSION 7) -set(OCTOVIS_PATCH_VERSION 2) +set(OCTOVIS_MINOR_VERSION 8) +set(OCTOVIS_PATCH_VERSION 0) set(OCTOVIS_VERSION ${OCTOVIS_MAJOR_VERSION}.${OCTOVIS_MINOR_VERSION}.${OCTOVIS_PATCH_VERSION}) set(OCTOVIS_SOVERSION ${OCTOVIS_MAJOR_VERSION}.${OCTOVIS_MINOR_VERSION}) # get rid of a useless warning: diff --git a/octovis/package.xml b/octovis/package.xml index b8cdaa9e..57567556 100644 --- a/octovis/package.xml +++ b/octovis/package.xml @@ -1,6 +1,6 @@ octovis - 1.7.2 + 1.8.0 octovis is visualization tool for the OctoMap library based on Qt and libQGLViewer. See http://octomap.github.io for details.