|
def | mse (x, points, distances) |
|
Class to extend the functionality of the Positioning class with UWB ranging capabilities.
Definition at line 20 of file src/ros_ips/positioning_plus.py.
def ros_ips.positioning_plus.PositioningPlus.__init__ |
( |
|
self, |
|
|
|
config_dir, |
|
|
|
min_beacons = 4 , |
|
|
|
max_z = None |
|
) |
| |
Initialize the class with zone and beacon definitions from YAML configuration file.
:param config_dir: String: Directory of the YAML config file
:param min_beacons: Int: Minimum number of beacons to use for trilateration
:param max_z: Float: Maximum z position the receiver can have after ranging
Definition at line 27 of file src/ros_ips/positioning_plus.py.
def ros_ips.positioning_plus.PositioningPlus.get_range |
( |
|
self, |
|
|
|
responses |
|
) |
| |
def ros_ips.positioning_plus.PositioningPlus.get_top_beacons |
( |
|
self, |
|
|
|
pings, |
|
|
|
n |
|
) |
| |
Get the top n beacons in terms of RSSI values from a list of beacon pings.
:param pings: [String]: list of beacon pings
:param n: Int: Number of top beacons to return
:return: [Beacon]: list of beacon objects ordered according to RSSI values
Definition at line 46 of file src/ros_ips/positioning_plus.py.
def ros_ips.positioning_plus.PositioningPlus.in_range |
( |
|
self, |
|
|
|
pings |
|
) |
| |
Get a list of beacons that are in range and are configured in the configuration YAML file from a list of
beacon pings recorded over a short duration. The returned beacons (EIDs can be used for UWB ranging)
:param pings: [String]: List of BCN pings
:return: [String]: List of EIDs that can be used for ranging
Definition at line 98 of file src/ros_ips/positioning_plus.py.
def ros_ips.positioning_plus.PositioningPlus.mse |
( |
|
x, |
|
|
|
points, |
|
|
|
distances |
|
) |
| |
|
static |
Cost-function to use for position estimation. Minimize the squared error of the distance between a variable
point x and each beacon and the measured UWB distance. mse = SUM(distance - dist(x, points)^2
:param x: [Float, Float, Float]: vector with variable components to be optimized
:param points: [[x, y, z], ...]: list of positions of the beacons used for UWB ranging
:param distances: [Float]: estimated distances from UWB ranging of above beacons
:return: Float: mean squared error for all beacon positions
Definition at line 151 of file src/ros_ips/positioning_plus.py.
def ros_ips.positioning_plus.PositioningPlus.parse_srg |
( |
|
self, |
|
|
|
responses |
|
) |
| |
Parse a list of SRG ranging responses of UWB beacons. For each message (if it is valid) return the positions,
frame id and estimated ranges.
:param responses: [String]: list of SRG responses from UWB beacons
:return: [(Beacon, Float)]: list beacon-object and range pairs
Definition at line 74 of file src/ros_ips/positioning_plus.py.
def ros_ips.positioning_plus.PositioningPlus.trilaterate |
( |
|
self, |
|
|
|
ranges |
|
) |
| |
Estimate the position of the receiver by using trilateration with at least three UWB responses
:param ranges: [([Float, Float, Float], Float)]: list of position and range pairs (obtained from parse_srg) or
[(Beacon, Float)]: list of beacon object and range pairs (output from parse_srg())
:return: [Float, Float, Float]: 3D coordinates of estimated receiver location
Definition at line 114 of file src/ros_ips/positioning_plus.py.
ros_ips.positioning_plus.PositioningPlus.eids |
ros_ips.positioning_plus.PositioningPlus.max_z |
ros_ips.positioning_plus.PositioningPlus.min_beacons |
ros_ips.positioning_plus.PositioningPlus.minimization_params |
|
static |
The documentation for this class was generated from the following file: