ArmRotationWidget.cpp
Go to the documentation of this file.
00001 /****************************************************************************
00002 **
00003 ** Copyright (C) 2010 Nokia Corporation and/or its subsidiary(-ies).
00004 ** All rights reserved.
00005 ** Contact: Nokia Corporation (qt-info@nokia.com)
00006 **
00007 ** This file is part of the examples of the Qt Toolkit.
00008 **
00009 ** $QT_BEGIN_LICENSE:BSD$
00010 ** You may use this file under the terms of the BSD license as follows:
00011 **
00012 ** "Redistribution and use in source and binary forms, with or without
00013 ** modification, are permitted provided that the following conditions are
00014 ** met:
00015 **   * Redistributions of source code must retain the above copyright
00016 **     notice, this list of conditions and the following disclaimer.
00017 **   * Redistributions in binary form must reproduce the above copyright
00018 **     notice, this list of conditions and the following disclaimer in
00019 **     the documentation and/or other materials provided with the
00020 **     distribution.
00021 **   * Neither the name of Nokia Corporation and its Subsidiary(-ies) nor
00022 **     the names of its contributors may be used to endorse or promote
00023 **     products derived from this software without specific prior written
00024 **     permission.
00025 **
00026 ** THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00027 ** "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00028 ** LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
00029 ** A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
00030 ** OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
00031 ** SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
00032 ** LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
00033 ** DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
00034 ** THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00035 ** (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
00036 ** OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE."
00037 ** $QT_END_LICENSE$
00038 **
00039 ****************************************************************************/
00040 
00041 #include "ArmRotationWidget.h"
00042 
00043 #include <math.h>
00044 #include <QtGui>
00045 #include "corobot.h"
00046 
00047 
00048 //Constant related to the drawings
00049 const int ARM_X = 120;
00050 const int ARM_Y = 120;
00051 const int ARM_CENTER_X = ARM_X / 2;
00052 const int ARM_BODY_TOP = ARM_X * 7 / 10;
00053 const int ARM_SHOULDER_X = ARM_CENTER_X - ARM_X / 7;
00054 const int SIZE_ARM = 25; //the value does not match the size of the real arm. 
00055 const int LENGTH_ROBOT = 55; //the value does not match the size of the real robot.
00056 const int WIDTH_ROBOT = 40; //the value does not match the size of the real robot.
00057 ArmRotationWidget::ArmRotationWidget(QWidget *parent)
00058     : QGraphicsView(parent), timerId(0)
00059 {
00060 
00061     QGraphicsScene *scene = new QGraphicsScene(this);
00062     scene->setItemIndexMethod(QGraphicsScene::NoIndex);
00063     scene->setSceneRect(0, 00, 210, 110);
00064 
00065     setScene(scene);
00066     setCacheMode(CacheBackground);
00067     setViewportUpdateMode(BoundingRectViewportUpdate);
00068     setRenderHint(QPainter::Antialiasing);
00069     setTransformationAnchor(AnchorUnderMouse);
00070     scale(qreal(1), qreal(1));
00071     setMinimumSize(210, 110);
00072     setWindowTitle(tr("Elastic Nodes"));
00073 
00074     joint *joint1 = new joint(this);
00075     joint *joint2 = new joint(this);
00076 
00077     scene->addItem(joint1);
00078     scene->addItem(joint2);
00079 
00080     joint2->setFlag(joint2->ItemIsMovable);
00081 
00082 
00083     joint1->setPos(this->sceneRect().right()/2 + 5, this->sceneRect().bottom()-10 - LENGTH_ROBOT * 4/5 +5);
00084     joint2->setPos(this->sceneRect().right()/2 + 5,this->sceneRect().bottom()-10 - LENGTH_ROBOT * 4/5 +5 - SIZE_ARM);
00085 
00086     end_effector = QPointF(0,0);
00087 
00088     QGraphicsLineItem *line = new QGraphicsLineItem(joint1->pos().x()-5,joint1->pos().y()-5,joint2->pos().x()-5,joint2->pos().y()-5);
00089     scene->addItem(line);
00090 
00091  }
00092 
00093 
00094 void ArmRotationWidget::itemMoved()
00095 //timer starts if a movement is detected
00096 {
00097     if (!timerId)
00098         timerId = startTimer(1000 / 25);
00099 }
00100 
00101 
00102 
00103 void ArmRotationWidget::moveArmLeft()
00104 //moves the arm toward the robot
00105 {
00106     this->scene()->items().at(2)->setPos(end_effector + QPointF(-5,0));
00107 }
00108 
00109 void ArmRotationWidget::moveArmRight()
00110 //moves the arm far from the robot
00111 {
00112     this->scene()->items().at(2)->setPos(end_effector + QPointF(5,0));
00113 }
00114 
00115 
00116 void ArmRotationWidget::timerEvent(QTimerEvent *event)
00117 //execute this function when the timer is up.
00118  {
00119      Q_UNUSED(event);
00120      double angle;
00121 
00122      QList<joint *> joints;
00123          foreach (QGraphicsItem *item, scene()->items()) {
00124              if (joint *j = qgraphicsitem_cast<joint *>(item))
00125                  joints << j;
00126          }
00127 
00128 
00129          if(joints.at(1)->x()!=end_effector.x() || joints.at(1)->y()!=end_effector.y()){
00130              double t1,t2;
00131              double x = joints.at(0)->x() - joints.at(1)->x();
00132              double y = joints.at(0)->y() - joints.at(1)->y();
00133                 
00134              if(y > 0)
00135              {
00136                 angle = atan(x/y) + M_PI/2;
00137                 joints.at(1)->setPos(this->sceneRect().right()/2 + 5 + cos(angle)*SIZE_ARM, this->sceneRect().bottom()-10 - LENGTH_ROBOT * 4/5 +5 - sin(angle)*SIZE_ARM);
00138                 emit armAngle_rad(angle);
00139              }
00140              else
00141                 joints.at(1)->setPos(end_effector);
00142 
00143 
00144              QList<QGraphicsLineItem *> lines;
00145              foreach (QGraphicsItem *item, scene()->items()) {
00146                 if (QGraphicsLineItem *l = qgraphicsitem_cast<QGraphicsLineItem *>(item))
00147                         lines << l;
00148              }
00149 
00150              lines.at(0)->setLine(joints.at(0)->pos().x()-5,joints.at(0)->pos().y()-5,joints.at(1)->pos().x()-5,joints.at(1)->pos().y()-5);
00151 
00152              end_effector = joints.at(1)->pos();
00153          }
00154                 
00155 
00156  }
00157 
00158 
00159  void ArmRotationWidget::drawBackground(QPainter *painter, const QRectF &rect)
00160  // draw the widget background
00161  {
00162      Q_UNUSED(rect);
00163 
00164      // Shadow
00165      QRectF sceneRect = this->sceneRect();
00166      QRectF rightShadow(sceneRect.right(), sceneRect.top() + 5, 5, sceneRect.height());
00167      QRectF bottomShadow(sceneRect.left() + 5, sceneRect.bottom(), sceneRect.width(), 5);
00168      if (rightShadow.intersects(rect) || rightShadow.contains(rect))
00169          painter->fillRect(rightShadow, Qt::darkGray);
00170      if (bottomShadow.intersects(rect) || bottomShadow.contains(rect))
00171          painter->fillRect(bottomShadow, Qt::darkGray);
00172 
00173 
00174      // Fill
00175      QLinearGradient gradient(sceneRect.topLeft(), sceneRect.bottomRight());
00176      gradient.setColorAt(0, Qt::white);
00177      gradient.setColorAt(1, Qt::lightGray);
00178      painter->fillRect(rect.intersect(sceneRect), gradient);
00179      painter->setBrush(Qt::NoBrush);
00180      painter->drawRect(sceneRect);
00181 
00182      //Robot
00183       QRectF robot((sceneRect.right() - sceneRect.left())/2 - WIDTH_ROBOT/2, sceneRect.bottom()-LENGTH_ROBOT-10, WIDTH_ROBOT, LENGTH_ROBOT);
00184       painter->fillRect(robot, Qt::gray);
00185       painter->setBrush(Qt::NoBrush);
00186       painter->drawRect(robot);
00187 
00188 
00189      // Text
00190      QRectF textRect(sceneRect.left() + 4, sceneRect.top() + 4,
00191                      sceneRect.width() - 4, sceneRect.height() - 4);
00192 
00193      QFont font = painter->font();
00194      font.setBold(true);
00195      font.setPointSize(14);
00196      painter->setFont(font);
00197      painter->setPen(Qt::lightGray);
00198      painter->setPen(Qt::black);
00199  }
00200 
00201  void ArmRotationWidget::scaleView(qreal scaleFactor)
00202  //scale the view
00203  {
00204      qreal factor = transform().scale(scaleFactor, scaleFactor).mapRect(QRectF(0, 0, 1, 1)).width();
00205      if (factor < 0.07 || factor > 100)
00206          return;
00207 
00208      scale(scaleFactor, scaleFactor);
00209  }


corobot_teleop
Author(s): Morgan Cormier/Gang Li/mcormier@coroware.com
autogenerated on Tue Jan 7 2014 11:39:41