File: visp_tracker/Init.srv
# Initialize the tracking.
#
# During the initialization the tracked object is chosen and its
# initial pose is required to start the tracking.
#
# The model is retrieved through the parameter server using the
# model_description parameter.
# Object initial pose.
geometry_msgs/Transform initial_cMo
# Tracking parameters
MovingEdge moving_edge
---
# Did the initialization succeed?
bool initialization_succeed
Expanded Definition
geometry_msgs/Transform initial_cMo
geometry_msgs/Vector3 translation
float64 x
float64 y
float64 z
geometry_msgs/Quaternion rotation
float64 x
float64 y
float64 z
float64 w
MovingEdge moving_edge
int64 mask_size
int64 n_mask
int64 range
float64 threshold
float64 mu1
float64 mu2
int64 sample_step
int64 ntotal_sample
int64 strip
float64 min_samplestep
float64 aberration
float64 init_aberration
float64 lambda
float64 first_threshold
bool initialization_succeed