articulation_msgs/ModelMsg Message

File: articulation_msgs/ModelMsg.msg

# Single kinematic model
#
# A kinematic model is defined by its model class name, and a set of parameters. 
# The client may additionally specify a model id, that can be used to colorize the
# model when visualized using the RVIZ model display.

# For a list of currently implemented models, see the documetation at
# http://www.ros.org/wiki/articulation_models
#
#

Header header                        # frame and timestamp

int32 id                             # user specified model id
string name                          # name of the model family (e.g. "rotational",
                                     # "prismatic", "pca-gp", "rigid")
articulation_msgs/ParamMsg[] params  # model parameters
articulation_msgs/TrackMsg track     # trajectory from which the model is estimated, or
                                     # that is evaluated using the model

Expanded Definition

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