Package lejos.robotics.navigation
Class Pose
- java.lang.Object
-
- lejos.robotics.navigation.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
-
-
Method Summary
All Methods Instance Methods Concrete Methods Modifier and Type Method Description floatangleTo(Point destination)Returns the angle with respect to the X axis tovoidarcUpdate(float distance, float turnAngle)Sets the pose location and heading to the correct values resulting from travel in a circular arc.floatdistanceTo(Point destination)Return the distance to the destinationvoiddumpObject(java.io.DataOutputStream dos)floatgetHeading()returns the heading (direction angle) of the PosePointgetLocation()Get the location as a PointfloatgetX()Get the X coordinatefloatgetY()Get the Y coordinatevoidloadObject(java.io.DataInputStream dis)voidmoveUpdate(float distance)Move the specified distance in the direction of current heading.PointpointAt(float distance, float bearing)Returns the point atdistancefrom the location of this pose, in the directionbearingrelative to the X axis.floatrelativeBearing(Point destination)Returns the angle todestinationrelative to the pose heading;voidrotateUpdate(float angle)Rotate the heading through the specified anglevoidsetHeading(float heading)voidsetLocation(float x, float y)Sets the location of this pose to a new point at x,y;voidsetLocation(Point p)Set the location of the posejava.lang.StringtoString()return string contains x,y and headingvoidtranslate(float dx, float dy)Change the x and y coordinates of the pose by adding dx and dy.
-
-
-
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 coordinatey- the Y coordinateheading- 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 coordinatedy- 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 traveledturnAngle- the angle turned
-
angleTo
public float angleTo(Point destination)
Returns the angle with respect to the X axis tofrom the current location of this pose. - Parameters:
destination-- Returns:
- angle in degrees
-
relativeBearing
public float relativeBearing(Point destination)
Returns the angle todestinationrelative 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 atdistancefrom the location of this pose, in the directionbearingrelative to the X axis.- Parameters:
distance- the distance to the pointbearing- 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:
toStringin classjava.lang.Object- Returns:
- x,y,heading
-
dumpObject
public void dumpObject(java.io.DataOutputStream dos) throws java.io.IOException- Specified by:
dumpObjectin interfaceTransmittable- Throws:
java.io.IOException
-
loadObject
public void loadObject(java.io.DataInputStream dis) throws java.io.IOException- Specified by:
loadObjectin interfaceTransmittable- Throws:
java.io.IOException
-
-