Class Pose

  • All Implemented Interfaces:
    Transmittable

    public class Pose
    extends java.lang.Object
    implements Transmittable
    Represents the location and heading(direction angle) of a robot.
    This class includes methods for updating the Pose to in response to basic robot movements. It also contains utility methods for use in navigation, such as the direction and distance to a point from the location of the pose, and also the location of a point at a given distance and direction from the location of the pose.
    All directions and angles are in degrees and use the standard convention in mathematics: direction 0 is parallel to the X axis, and direction +90 is parallel to the Y axis.
    Author:
    Roger Glassey
    • Field Summary

      Fields 
      Modifier and Type Field Description
      protected float _heading  
      protected Point _location  
      protected static java.lang.String format  
    • Constructor Summary

      Constructors 
      Constructor Description
      Pose()
      allocate a new Pose at the origin, heading = 0:the direction the positive X axis
      Pose​(float x, float y, float heading)
      Allocate a new pose at location (x,y) with specified heading in degrees.
    • Method Summary

      All Methods Instance Methods Concrete Methods 
      Modifier and Type Method Description
      float angleTo​(Point destination)
      Returns the angle with respect to the X axis to
      void arcUpdate​(float distance, float turnAngle)
      Sets the pose location and heading to the correct values resulting from travel in a circular arc.
      float distanceTo​(Point destination)
      Return the distance to the destination
      void dumpObject​(java.io.DataOutputStream dos)  
      float getHeading()
      returns the heading (direction angle) of the Pose
      Point getLocation()
      Get the location as a Point
      float getX()
      Get the X coordinate
      float getY()
      Get the Y coordinate
      void loadObject​(java.io.DataInputStream dis)  
      void moveUpdate​(float distance)
      Move the specified distance in the direction of current heading.
      Point pointAt​(float distance, float bearing)
      Returns the point at distance from the location of this pose, in the direction bearing relative to the X axis.
      float relativeBearing​(Point destination)
      Returns the angle to destination relative to the pose heading;
      void rotateUpdate​(float angle)
      Rotate the heading through the specified angle
      void setHeading​(float heading)  
      void setLocation​(float x, float y)
      Sets the location of this pose to a new point at x,y;
      void setLocation​(Point p)
      Set the location of the pose
      java.lang.String toString()
      return string contains x,y and heading
      void translate​(float dx, float dy)
      Change the x and y coordinates of the pose by adding dx and dy.
      • Methods inherited from class java.lang.Object

        clone, equals, finalize, getClass, hashCode, notify, notifyAll, wait, wait, wait
    • Field Detail

      • _location

        protected Point _location
      • _heading

        protected float _heading
      • format

        protected static java.lang.String format
    • Constructor Detail

      • Pose

        public Pose()
        allocate a new Pose at the origin, heading = 0:the direction the positive X axis
      • Pose

        public Pose​(float x,
                    float y,
                    float heading)
        Allocate a new pose at location (x,y) with specified heading in degrees.
        Parameters:
        x - the X coordinate
        y - the Y coordinate
        heading - the heading
    • Method Detail

      • rotateUpdate

        public void rotateUpdate​(float angle)
        Rotate the heading through the specified angle
        Parameters:
        angle -
      • moveUpdate

        public void moveUpdate​(float distance)
        Move the specified distance in the direction of current heading.
        Parameters:
        distance - to move
      • translate

        public void translate​(float dx,
                              float dy)
        Change the x and y coordinates of the pose by adding dx and dy.
        Parameters:
        dx - change in x coordinate
        dy - change in y coordinate
      • arcUpdate

        public void arcUpdate​(float distance,
                              float turnAngle)
        Sets the pose location and heading to the correct values resulting from travel in a circular arc. The radius is calculated from the distance and turn angle
        Parameters:
        distance - the distance traveled
        turnAngle - the angle turned
      • angleTo

        public float angleTo​(Point destination)
        Returns the angle with respect to the X axis to from the current location of this pose.
        Parameters:
        destination -
        Returns:
        angle in degrees
      • relativeBearing

        public float relativeBearing​(Point destination)
        Returns the angle to destination relative to the pose heading;
        Parameters:
        destination - the target point
        Returns:
        the relative bearing of the destination, between -180 and 180
      • distanceTo

        public float distanceTo​(Point destination)
        Return the distance to the destination
        Parameters:
        destination -
        Returns:
        the distance
      • pointAt

        public Point pointAt​(float distance,
                             float bearing)
        Returns the point at distance from the location of this pose, in the direction bearing relative to the X axis.
        Parameters:
        distance - the distance to the point
        bearing - the true bearing of the point
        Returns:
        point
      • getHeading

        public float getHeading()
        returns the heading (direction angle) of the Pose
        Returns:
        the heading
      • getX

        public float getX()
        Get the X coordinate
        Returns:
        the X coordinate
      • getY

        public float getY()
        Get the Y coordinate
        Returns:
        the Y coordinate
      • getLocation

        public Point getLocation()
        Get the location as a Point
        Returns:
        the location as a point
      • setLocation

        public void setLocation​(Point p)
        Set the location of the pose
        Parameters:
        p - the new location
      • setLocation

        public void setLocation​(float x,
                                float y)
        Sets the location of this pose to a new point at x,y;
        Parameters:
        x -
        y -
      • setHeading

        public void setHeading​(float heading)
      • toString

        public java.lang.String toString()
        return string contains x,y and heading
        Overrides:
        toString in class java.lang.Object
        Returns:
        x,y,heading
      • dumpObject

        public void dumpObject​(java.io.DataOutputStream dos)
                        throws java.io.IOException
        Specified by:
        dumpObject in interface Transmittable
        Throws:
        java.io.IOException
      • loadObject

        public void loadObject​(java.io.DataInputStream dis)
                        throws java.io.IOException
        Specified by:
        loadObject in interface Transmittable
        Throws:
        java.io.IOException