Attitude sensor¶
This sensor is an high-level sensor, returning the attitude of the sensor (i.e. angles and angular velocities). It can be seen as the integration of an IMU, or a couple gyroscope/gyrometer.
If the robot has a physics controller, the velocities are directly
read from its property localAngularVelocity
. Otherwise the
velocities are calculated by simple differentiation. The
measurements are given in the sensor coordinate system.
Configuration parameters for Attitude sensor¶
You can set these properties in your scripts with <component>.properties(<property1>=..., <property2>=...)
.
UseAngleAgainstNorth
(bool, default:False
)- If set to true, return the absolute yaw against North. The whole geodetic coordinates (longitude, latitude, altitude, angle_against_north) must be configured. Otherwise, return the yaw against the Blender coordinates
ComputationMode
(string, default:"Automatic"
)- Kind of computation, can be one of [‘Velocity’, ‘Position’]. Only robot with dynamic and Velocity control can choose Velocity computation. Default choice is Velocity for robot with physics, and Position for others
Data fields¶
This sensor exports these datafields at each simulation step:
timestamp
(float, initial value:0.0
)- number of seconds in simulated time
rotation
(Euler angles (XYZ), initial value:[0.0, 0.0, 0.0]
)- rotation of the sensor, in radian
angular_velocity
(vec3<float>, initial value:[0.0, 0.0, 0.0]
)- rates in the sensors axis x, y, z axes (in radian . sec ^ -1)
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
)mavlink
as AttitudeSensor (morse.middleware.mavlink.attitude.AttitudeSensor
)
Services for Attitude sensor¶
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
attitude = Attitude()
# place your component at the correct location
attitude.translate(<x>, <y>, <z>)
attitude.rotate(<rx>, <ry>, <rz>)
robot.append(attitude)
# define one or several communication interface, like 'socket'
attitude.add_interface(<interface>)
env = Environment('empty')
Other sources of examples¶
(This page has been auto-generated from MORSE module morse.sensors.attitude.)