Odometry¶
An odometry sensor that returns raw, partially integrated or fully integrated displacement information.
This sensor produces relative displacement with respect to the position and rotation in the previous Blender tick. It can compute too the position of the robot with respect to its original position, and the associated speed.
The angles for yaw, pitch and roll are given in radians.
Note
This sensor always provides perfect data. To obtain more realistic readings, it is recommended to add modifiers.
- Noise modifier: Adds random Gaussian noise to the data
- Odometry Noise modifier: Simulate scale factor error and gyroscope drift
Configuration parameters for Odometry¶
No configurable parameter.
Available functional levels¶
Functional levels are predefined abstraction or realism levels for the sensor.
raw
raw odometry: only dS is exportedAt this level, the sensor exports these datafields at each simulation step:
dS
(float, initial value:0.0
): curvilinear distance since last tick
Interface support:
socket
as straight JSON serialization (morse.middleware.socket_datastream.SocketPublisher
)moos
as StringPublisher (morse.middleware.moos.abstract_moos.StringPublisher
)yarp
as YarpPublisher (morse.middleware.yarp_datastream.YarpPublisher
)text
as key = value format with timestamp and index value (morse.middleware.text_datastream.Publisher
)
differential
differential odometry, corresponding to standard ‘robot level’ odometryAt this level, the sensor exports these datafields at each simulation step:
dx
(float, initial value:0.0
): delta of X coordinate of the sensordy
(float, initial value:0.0
): delta of Y coordinate of the sensordz
(float, initial value:0.0
): delta of Z coordinate of the sensordyaw
(float, initial value:0.0
): delta of rotation angle with respect to the Z axisdpitch
(float, initial value:0.0
): delta of rotation angle with respect to the Y axisdroll
(float, initial value:0.0
): delta of rotation angle with respect to the X axis
Interface support:
socket
as straight JSON serialization (morse.middleware.socket_datastream.SocketPublisher
)yarp
as YarpPublisher (morse.middleware.yarp_datastream.YarpPublisher
)moos
as StringPublisher (morse.middleware.moos.abstract_moos.StringPublisher
)text
as key = value format with timestamp and index value (morse.middleware.text_datastream.Publisher
)
integrated
(default level) integrated odometry: absolution position is exportedAt this level, the sensor exports these datafields at each simulation step:
x
(float, initial value:0.0
): X coordinate of the sensory
(float, initial value:0.0
): Y coordinate of the sensorz
(float, initial value:0.0
): Z coordinate of the sensoryaw
(float, initial value:0.0
): rotation angle with respect to the Z axispitch
(float, initial value:0.0
): rotation angle with respect to the Y axisroll
(float, initial value:0.0
): rotation angle with respect to the X axisvx
(float, initial value:0.0
): linear velocity related to the X coordinate of the sensorvy
(float, initial value:0.0
): linear velocity related to the Y coordinate of the sensorvz
(float, initial value:0.0
): linear velocity related to the Z coordinate of the sensorwz
(float, initial value:0.0
): angular velocity related to the Z coordinate of the sensorwy
(float, initial value:0.0
): angular velocity related to the Y coordinate of the sensorwx
(float, initial value:0.0
): angular velocity related to the X coordinate of the sensor
Interface support:
ros
as nav_msgs/Odometry (morse.middleware.ros.odometry.OdometryPublisher
)socket
as straight JSON serialization (morse.middleware.socket_datastream.SocketPublisher
)moos
as StringPublisher (morse.middleware.moos.abstract_moos.StringPublisher
)yarp
as YarpPublisher (morse.middleware.yarp_datastream.YarpPublisher
)text
as key = value format with timestamp and index value (morse.middleware.text_datastream.Publisher
)pocolibs
as POM_ME_POS (morse.middleware.pocolibs.sensors.pom.PomSensorPoster
) or as POM_POS (morse.middleware.pocolibs.sensors.pom.PomPoster
)mavlink
as OdometrySensor (morse.middleware.mavlink.odometry_to_local_ned.OdometrySensor
)
Services for Odometry¶
get_configurations()
(blocking)Returns the configurations of a component (parsed from the properties).
Return value
a dictionary of the current component’s configurations
get_local_data()
(blocking)Returns the current data stored in the sensor.
Return value
a dictionary of the current sensor’s data
get_properties()
(blocking)Returns the properties of a component.
Return value
a dictionary of the current component’s properties
set_property(prop_name, prop_val)
(blocking)Modify one property on a component
Parameters
prop_name
: the name of the property to modify (as shown the documentation)prop_val
: the new value of the property. Note that there is no checking about the type of the value so be careful
Return value
nothing
Examples¶
The following examples show how to use this component in a Builder script:
from morse.builder import *
# adds a default robot (the MORSE mascott!)
robot = Morsy()
# creates a new instance of the sensor
odometry = Odometry()
# place your component at the correct location
odometry.translate(<x>, <y>, <z>)
odometry.rotate(<rx>, <ry>, <rz>)
# select a specific abstraction level (cf below), or skip it to use default level
odometry.level(<level>)
robot.append(odometry)
# define one or several communication interface, like 'socket'
odometry.add_interface(<interface>)
env = Environment('empty')
Other sources of examples¶
(This page has been auto-generated from MORSE module morse.sensors.odometry.)