| 
    Roomba Controller Dashboard 1
    
   A GUI and TCP client application that is used to control a Roomba for Computer Engineering 2880 @ Iowa State 
   | 
 
#include <Pose2D.hpp>
Public Member Functions | |
| Pose2D (double x, double y, double heading) | |
| Pose2D (double x, double y) | |
| Pose2D () | |
| Pose2D (const Pose2D &position) | |
| double | angleTo (const Pose2D &other) const | 
| double | distanceTo (const Pose2D &other) const | 
| double | squareOfDistanceTo (const Pose2D &other) const | 
| Pose2D | clone () const | 
| void | rotateByPose (const Pose2D &rotation) | 
| void | rotateByAngle (double angle) | 
| void | translateByPose (const Pose2D &translation) | 
| void | translateByMagnitude (double magnitude) | 
| void | transformPose (const Pose2D &modifier) | 
| double | getX () const | 
| double | getY () const | 
| double | getHeading () const | 
| void | setHeading (double angle) | 
| void | plusCoord (const Pose2D &other) | 
| void | plus (const Pose2D &other) | 
| void | minus (Pose2D other) | 
| void | addAngle (double angle) | 
| Pose2D | subtractBy (const Pose2D &other) const | 
| Pose2D | scaleBy (double scaler) const | 
| Pose2D | normalize () const | 
| double | dotProduct (const Pose2D &other) const | 
| void | setX (double x) | 
| void | vecAdd (double angle, double magnitude) | 
| void | setY (double y) | 
| uint8_t | getQuadrant () const | 
| void | wrapHeading () | 
| void | transformForPose (const Pose2D &other) | 
| bool | isOnLine (Pose2D LineEnd1, Pose2D LineEnd2) | 
| bool | isPerpendicularToLine (double m) | 
| void | multiply (double d) | 
Static Public Member Functions | |
| static Pose2D | fromPolar (double magnitude, double angle) | 
| static double | degreesToRadians (double degrees) | 
| static double | radiansToDegrees (double radians) | 
| static Pose2D | parseFromStream (std::istringstream &stream) | 
| static double | getAngleBetweenPoints (Pose2D corner, Pose2D end1, Pose2D end2) | 
Protected Attributes | |
| double | x | 
| double | y | 
| double | heading | 
Friends | |
| std::ostream & | operator<< (std::ostream &os, const Pose2D &d) | 
A class representing a 2D position and a heading. Implements common vector functions
Definition at line 23 of file Pose2D.hpp.
| Pose2D::Pose2D | ( | double | x, | 
| double | y, | ||
| double | heading ) | 
Consctructs a new Pose2D object
| x | the x component | 
| y | the y component | 
| heading | the heading | 
Definition at line 7 of file Pose2D.cpp.
| Pose2D::Pose2D | ( | double | x, | 
| double | y ) | 
Constructs a new Pose2D object
| x | component | 
| y | component | 
Definition at line 13 of file Pose2D.cpp.
| Pose2D::Pose2D | ( | ) | 
Makes a new Pose2D with 0's as default
Definition at line 18 of file Pose2D.cpp.
| Pose2D::Pose2D | ( | const Pose2D & | position | ) | 
Constructs a new Pose2D. Copy constructor.
| position | the pose to copy | 
Definition at line 64 of file Pose2D.cpp.
| void Pose2D::addAngle | ( | double | angle | ) | 
Add the angle to heading
| angle | gets added to "this" heading | 
Definition at line 82 of file Pose2D.cpp.
| double Pose2D::angleTo | ( | const Pose2D & | other | ) | const | 
Calculates the angle from one node to another
| other | angle to get to | 
Definition at line 78 of file Pose2D.cpp.
| Pose2D Pose2D::clone | ( | ) | const | 
      
  | 
  static | 
Calculates the radian equivalent of degrees
| degrees | the angle in degrees | 
Definition at line 200 of file Pose2D.cpp.
| double Pose2D::distanceTo | ( | const Pose2D & | other | ) | const | 
Calculates the distance between two nodes
| other | the other node to calculate the distance to | 
Definition at line 86 of file Pose2D.cpp.
| double Pose2D::dotProduct | ( | const Pose2D & | other | ) | const | 
Calculate the dot product from the nodes: "this" and other
| other | other node to calculate the dot product with | 
Definition at line 226 of file Pose2D.cpp.
      
  | 
  static | 
Creates a new Pose2D from polar coordinats
| magnitude | the magnitude of the position | 
| angle | the angle of the position | 
Definition at line 193 of file Pose2D.cpp.
gets the angle between points in radians.
| corner | |
| end1 | |
| end2 | 
| double Pose2D::getHeading | ( | ) | const | 
get the heading of the position
Definition at line 155 of file Pose2D.cpp.
| uint8_t Pose2D::getQuadrant | ( | ) | const | 
Gets the quadrant that a Pose is in. If the pose is on the origin or on an intercept it return's 0. otherwise going from pos pos (1) it travels counter clockwise around in a circle
Definition at line 171 of file Pose2D.cpp.
| double Pose2D::getX | ( | ) | const | 
get the x component of the position
Definition at line 147 of file Pose2D.cpp.
| double Pose2D::getY | ( | ) | const | 
gets the y component of the position
Definition at line 151 of file Pose2D.cpp.
Makes a slope intercept object from two pose2Ds
| one | the first position | 
| two | the second position | 
| LineEnd1 | one endpoint of the line | 
| LineEnd2 | the other endpoint of the line | 
Definition at line 24 of file Pose2D.cpp.
| bool Pose2D::isPerpendicularToLine | ( | double | m | ) | 
Determines whether a position is perpendicular to a given line
| void Pose2D::minus | ( | Pose2D | other | ) | 
Subtract this by other. Subtracts the components
| other | the other node to subtract by | 
Definition at line 187 of file Pose2D.cpp.
| void Pose2D::multiply | ( | double | d | ) | 
Multiplys the x and y components by a scalar
Definition at line 267 of file Pose2D.cpp.
| Pose2D Pose2D::normalize | ( | ) | const | 
Normalizes a position to a unit vector
Definition at line 221 of file Pose2D.cpp.
      
  | 
  static | 
Parse a pose 2d from a string stream
| stream | the stream to parse from | 
Definition at line 204 of file Pose2D.cpp.
| void Pose2D::plus | ( | const Pose2D & | other | ) | 
Computes a vector addition. Adds components of vectors together
| other | the other pose | 
Definition at line 100 of file Pose2D.cpp.
| void Pose2D::plusCoord | ( | const Pose2D & | other | ) | 
      
  | 
  static | 
Calculates the degree equivalent of radians
| radians | the angle in radians | 
| void Pose2D::rotateByAngle | ( | double | angle | ) | 
Uses a rotation matrix to rotate a Pose2D by an angle. Rotates about the origin.
| angle | to rotate by. | 
Definition at line 116 of file Pose2D.cpp.
| void Pose2D::rotateByPose | ( | const Pose2D & | rotation | ) | 
Rotate a Pose2D by the a rotation cooresponding to the heading of the other pose
| rotation | the pose to rotate by | 
Definition at line 128 of file Pose2D.cpp.
| Pose2D Pose2D::scaleBy | ( | double | scaler | ) | const | 
Scales a position by another. Returs result
| scaler | amount to scale this vector as a pose by | 
Definition at line 217 of file Pose2D.cpp.
| void Pose2D::setHeading | ( | double | angle | ) | 
Sets the heading of the Pose
| angle | the angle to set the Pose at | 
Definition at line 159 of file Pose2D.cpp.
| void Pose2D::setX | ( | double | x | ) | 
| void Pose2D::setY | ( | double | y | ) | 
| double Pose2D::squareOfDistanceTo | ( | const Pose2D & | other | ) | const | 
calculate the squared distance to another object
| other | the object to get the squared distance to | 
Definition at line 90 of file Pose2D.cpp.
Subtract "this" from other by components and return the result
| other | the other node to subtract by | 
Definition at line 213 of file Pose2D.cpp.
| void Pose2D::transformForPose | ( | const Pose2D & | other | ) | 
transforms a given pose for another's frame
| other | the other frame | 
Definition at line 94 of file Pose2D.cpp.
| void Pose2D::transformPose | ( | const Pose2D & | modifier | ) | 
transform a position with a rotation and a translation
| modifier | the heading gets used as the rotation. The compoenent get used as the translation | 
Definition at line 142 of file Pose2D.cpp.
| void Pose2D::translateByMagnitude | ( | double | magnitude | ) | 
This is admitedly a bit of a goofy function. We take the magnitude of the translation and extend the current position by that much in the heading of the pose. I like to think of the Pose2D as a vector, then we take the heading and combine it into a pollar coordinate with the magnitude. Then we do vector addition on the Pose2D.
| magnitude | to extend by | 
Definition at line 137 of file Pose2D.cpp.
| void Pose2D::translateByPose | ( | const Pose2D & | translation | ) | 
Translation for a pose by another pose. Vector addition
| translation | the pose to add | 
Definition at line 132 of file Pose2D.cpp.
| void Pose2D::vecAdd | ( | double | angle, | 
| double | magnitude ) | 
Computes a vector addition from an angle and quantity
| angle | the angle component of the vector | 
| magnitude | the quantity component of the vector | 
Definition at line 110 of file Pose2D.cpp.
| void Pose2D::wrapHeading | ( | ) | 
Wraps a heading to - PI -> PI
Definition at line 235 of file Pose2D.cpp.
      
  | 
  friend | 
To string for a pose2D
| os | output stream | 
| d | the pose2D to reference | 
Definition at line 230 of file Pose2D.cpp.
      
  | 
  protected | 
Definition at line 25 of file Pose2D.hpp.
      
  | 
  protected | 
Definition at line 25 of file Pose2D.hpp.
      
  | 
  protected | 
Definition at line 25 of file Pose2D.hpp.