Velocity ======== This sensor returns the linear and angular velocity of the sensor, both in robot frame and in world frame. Linear velocities are expressed in meter . sec ^ -1 while angular velocities are expressed in radian . sec ^ -1. The sensor expects that the associated robot has a physics controller. .. cssclass:: properties morse-section Configuration parameters for Velocity ------------------------------------- You can set these properties in your scripts with ``.properties(=..., =...)``. - ``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 .. cssclass:: fields morse-section Data fields ----------- This sensor exports these datafields at each simulation step: - ``timestamp`` (float, initial value: ``0.0``) number of seconds in simulated time - ``linear_velocity`` (vec3, initial value: ``[0.0, 0.0, 0.0]``) velocity in sensor x, y, z axes (in meter . sec ^ -1) - ``angular_velocity`` (vec3, initial value: ``[0.0, 0.0, 0.0]``) rates in sensor x, y, z axes (in radian . sec ^ -1) - ``world_linear_velocity`` (vec3, initial value: ``[0.0, 0.0, 0.0]``) velocity in world x, y, z axes (in meter . sec ^ -1) *Interface support:* - :tag:`text` as key = value format with timestamp and index value (:py:mod:`morse.middleware.text_datastream.Publisher`) - :tag:`ros` as `geometry_msgs/TwistStamped `_ (:py:mod:`morse.middleware.ros.velocity.TwistStampedPublisher`) - :tag:`socket` as straight JSON serialization (:py:mod:`morse.middleware.socket_datastream.SocketPublisher`) - :tag:`yarp` as yarp::Bottle (:py:mod:`morse.middleware.yarp_datastream.YarpPublisher`) - :tag:`moos` as StringPublisher (:py:mod:`morse.middleware.moos.abstract_moos.StringPublisher`) .. cssclass:: services morse-section Services for Velocity --------------------- - ``get_properties()`` (blocking) Returns the properties of a component. - Return value a dictionary of the current component's properties - ``get_local_data()`` (blocking) Returns the current data stored in the sensor. - Return value a dictionary of the current sensor's data - ``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 - ``get_configurations()`` (blocking) Returns the configurations of a component (parsed from the properties). - Return value a dictionary of the current component's configurations .. cssclass:: examples morse-section Examples -------- The following examples show how to use this component in a *Builder* script: .. code-block:: python from morse.builder import * # adds a default robot (the MORSE mascott!) robot = Morsy() # creates a new instance of the sensor velocity = Velocity() # place your component at the correct location velocity.translate(, , ) velocity.rotate(, , ) robot.append(velocity) # define one or several communication interface, like 'socket' velocity.add_interface() env = Environment('empty') .. cssclass:: files morse-section Other sources of examples +++++++++++++++++++++++++ - `Source code <../../_modules/morse/sensors/velocity.html>`_ - `Unit-test <../../_modules/base/velocity_testing.html>`_ *(This page has been auto-generated from MORSE module morse.sensors.velocity.)*