articulation_msgs/AlignModelSrv Service

File: articulation_msgs/AlignModelSrv.srv

# Align a data trajectory to a model trajectory
#
# For more details, see the documentation of the
# model_learner_prior node of the articulation_models package,
# http://www.ros.org/wiki/articulation_models
#

articulation_msgs/ModelMsg model              # contains the model trajectory
articulation_msgs/ModelMsg data               # contains the data trajectory
---
articulation_msgs/ModelMsg model_aligned      # contains the transformed model
                                              # trajectory, that is now aligned to
                                              # the data trajectory
articulation_msgs/ModelMsg data_aligned       # contains the transformed data
                                              # trajectory, that is now aligned to
                                              # the model trajectory
float64[9] R                                  # rotation matrix
float64[3] T                                  # translation vector
float64 dist_rot                              # angle (in radians) of the rotation
float32 dist_trans                            # distance of the translation


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 data
    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_aligned
    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 data_aligned
    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
float64[9] R
float64[3] T
float64 dist_rot
float32 dist_trans