articulation_msgs/TrackModelSrv Service

File: articulation_msgs/TrackModelSrv.srv

# Generic service description for model fitting, selection, and evaluation for articulated links
#
# A client requests a model operation (like model fitting, model selection
# or model evaluation), by storing the observed trajectory in model.track.pose[],
# optionally specifying a model name in model.name and optional parameters in
# model.params. The nodes model_learner_srv and model_learner_prior offer
# various services. For more details, see the documentation at
# http://www.ros.org/wiki/articulation_models
#
#

articulation_msgs/ModelMsg model      # request (e.g., containing an observed
                                      # trajectory of an articulated object)
---
articulation_msgs/ModelMsg model      # response (e.g., after model fitting and
                                      # selection, contains the model name,
                                      # and the projection of the observed trajectory
                                      # on the model
 

Expanded Definition

articulation_msgs/ModelMsg model
    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

articulation_msgs/ModelMsg model
    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