Armature Pose Sensor¶
Returns the joint state of a MORSE armature
The sensor streams the joint state (ie, the rotation or translation value of each joint belonging to the armature) of its parent armature.
Note
This sensor must be added as a child of the armature you want to sense. See the Examples section below for an example.
This component only allows to read armature configuration. To change the armature pose, you need an armature actuator.
Important
To be valid, special care must be given when creating armatures. If you want to add new one, please carefully read the armature creation documentation.
Note
The data structure on datastream exported by the armature sensor depends on the armature. It is a dictionary of pair (joint name, joint value). Joint values are either radians (for revolute joints) or meters (for prismatic joints)
See also: armature actuator
Configuration parameters for Armature Pose Sensor¶
No configurable parameter.
Data fields¶
This sensor exports these datafields at each simulation step:
timestamp
(float, initial value:0.0
)- number of seconds in simulated time
Interface support:
ros
as sensor_msgs/JointState (morse.middleware.ros.jointstate.JointStatePublisher
)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
)
Services for Armature Pose 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_joint(joint)
(blocking)Returns the value of a given joint, either: - its absolute rotation in radian along its rotation axis, or - it absolute translation in meters along its translation axis.
Throws an exception if the joint does not exist.
- Parameters
joint
: the name of the joint in the armature.
get_joints()
(blocking)Returns the list of joints of the armature.
Return value
the (ordered) list of joints in the armature, from root to tip.
get_joints_length()
(blocking)Returns a dict with the armature joints’ names as key and and the corresponding bone length as value (in meters).
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
get_state()
(blocking)Returns the joint state of the armature, ie a dictionnary with joint names as key and the corresponding rotation or translation as value (respectively in radian or meters).
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:
robot = ATRV()
arm = KukaLWR()
robot.append(arm)
arm.translate(z=0.9)
arm_pose = ArmaturePose()
# the sensor is appended to the armature, *not* to the robot
arm.append(arm_pose)
Other sources of examples¶
(This page has been auto-generated from MORSE module morse.sensors.armature_pose.)