articulation_msgs/ArticulatedObjectMsg Message

File: articulation_msgs/ArticulatedObjectMsg.msg

Header header

articulation_msgs/TrackMsg[] parts    # observed trajectories for each object part 
articulation_msgs/ParamMsg[] params   # global parameters
articulation_msgs/ModelMsg[] models   # models, describing relationships between parts
visualization_msgs/MarkerArray markers # marker visualization of models/object 

Expanded Definition

Header header
    uint32 seq
    time stamp
    string frame_id
articulation_msgs/TrackMsg[] parts
    uint32 POSE_VISIBLE=1
    uint32 POSE_END_OF_SEGMENT=2
    Header header
        uint32 seq
        time stamp
        string frame_id
    int32 id
    geometry_msgs/Pose[] pose
        geometry_msgs/Point position
            float64 x
            float64 y
            float64 z
        geometry_msgs/Quaternion orientation
            float64 x
            float64 y
            float64 z
            float64 w
    geometry_msgs/Pose[] pose_projected
        geometry_msgs/Point position
            float64 x
            float64 y
            float64 z
        geometry_msgs/Quaternion orientation
            float64 x
            float64 y
            float64 z
            float64 w
    geometry_msgs/Pose[] pose_resampled
        geometry_msgs/Point position
            float64 x
            float64 y
            float64 z
        geometry_msgs/Quaternion orientation
            float64 x
            float64 y
            float64 z
            float64 w
    uint32[] pose_flags
    sensor_msgs/ChannelFloat32[] channels
        string name
        float32[] values
articulation_msgs/ParamMsg[] params
    uint8 PRIOR=0
    uint8 PARAM=1
    uint8 EVAL=2
    string name
    float64 value
    uint8 type
articulation_msgs/ModelMsg[] models
    Header header
        uint32 seq
        time stamp
        string frame_id
    int32 id
    string name
    articulation_msgs/ParamMsg[] params
        uint8 PRIOR=0
        uint8 PARAM=1
        uint8 EVAL=2
        string name
        float64 value
        uint8 type
    articulation_msgs/TrackMsg track
        uint32 POSE_VISIBLE=1
        uint32 POSE_END_OF_SEGMENT=2
        Header header
            uint32 seq
            time stamp
            string frame_id
        int32 id
        geometry_msgs/Pose[] pose
            geometry_msgs/Point position
                float64 x
                float64 y
                float64 z
            geometry_msgs/Quaternion orientation
                float64 x
                float64 y
                float64 z
                float64 w
        geometry_msgs/Pose[] pose_projected
            geometry_msgs/Point position
                float64 x
                float64 y
                float64 z
            geometry_msgs/Quaternion orientation
                float64 x
                float64 y
                float64 z
                float64 w
        geometry_msgs/Pose[] pose_resampled
            geometry_msgs/Point position
                float64 x
                float64 y
                float64 z
            geometry_msgs/Quaternion orientation
                float64 x
                float64 y
                float64 z
                float64 w
        uint32[] pose_flags
        sensor_msgs/ChannelFloat32[] channels
            string name
            float32[] values
visualization_msgs/MarkerArray markers
    visualization_msgs/Marker[] markers
        byte ARROW=0
        byte CUBE=1
        byte SPHERE=2
        byte CYLINDER=3
        byte LINE_STRIP=4
        byte LINE_LIST=5
        byte CUBE_LIST=6
        byte SPHERE_LIST=7
        byte POINTS=8
        byte TEXT_VIEW_FACING=9
        byte MESH_RESOURCE=10
        byte TRIANGLE_LIST=11
        byte ADD=0
        byte MODIFY=0
        byte DELETE=2
        Header header
            uint32 seq
            time stamp
            string frame_id
        string ns
        int32 id
        int32 type
        int32 action
        geometry_msgs/Pose pose
            geometry_msgs/Point position
                float64 x
                float64 y
                float64 z
            geometry_msgs/Quaternion orientation
                float64 x
                float64 y
                float64 z
                float64 w
        geometry_msgs/Vector3 scale
            float64 x
            float64 y
            float64 z
        std_msgs/ColorRGBA color
            float32 r
            float32 g
            float32 b
            float32 a
        duration lifetime
        bool frame_locked
        geometry_msgs/Point[] points
            float64 x
            float64 y
            float64 z
        std_msgs/ColorRGBA[] colors
            float32 r
            float32 g
            float32 b
            float32 a
        string text
        string mesh_resource
        bool mesh_use_embedded_materials