jsk_recognition_msgs

Summary

jsk_recognition_msgs
Version:

0.3.15

Description:

The jsk_recognition_msgs package

Maintainers:
  • Ryohei Ueda <ueda AT jsk DOT t DOT u-tokyo DOT ac DOT jp>
Licenses:
  • BSD
BuildDepends:
BuildtoolDepends:
 
BuildExportDepends:
 
ExecDepends:

Types

Message types

jsk_recognition_msgs/RotatedRectStamped
Field:
Header header
RotatedRect rect
jsk_recognition_msgs/ColorHistogramArray
Field:
Header header
ColorHistogram[] histograms
jsk_recognition_msgs/Line
Field:
  • x1 (float64) –
  • y1 (float64) –
  • x2 (float64) –
  • y2 (float64) –
float64 x1
float64 y1
float64 x2
float64 y2
jsk_recognition_msgs/Torus
Field:
Header header
bool failure
geometry_msgs/Pose pose
float64 large_radius
float64 small_radius
jsk_recognition_msgs/LineArray
Field:
Header header
Line[] lines
jsk_recognition_msgs/BoundingBoxArrayWithCameraInfo
Field:
Header header
BoundingBoxArray boxes
sensor_msgs/CameraInfo camera_info
jsk_recognition_msgs/WeightedPoseArray
Field:
Header header
float32[] weights
geometry_msgs/PoseArray poses
jsk_recognition_msgs/Rect
Field:
  • x (int32) –
  • y (int32) –
  • width (int32) –
  • height (int32) –
int32 x
int32 y
int32 width
int32 height
jsk_recognition_msgs/Histogram
Field:
Header header
float64[] histogram
jsk_recognition_msgs/BoundingBoxArray
Field:

BoundingBoxArray is a list of BoundingBox. You can use jsk_rviz_plugins to visualize BoungingBoxArray on rviz.

# BoundingBoxArray is a list of BoundingBox.
# You can use jsk_rviz_plugins to visualize BoungingBoxArray on rviz.
Header header
BoundingBox[] boxes
jsk_recognition_msgs/SlicedPointCloud
Field:
sensor_msgs/PointCloud2 point_cloud
uint8 slice_index
uint8 sequence_id
jsk_recognition_msgs/ClusterPointIndices
Field:

ClusterPointIndices is used to represent segmentation result. Simply put, ClusterPointIndices is a list of PointIndices.

# ClusterPointIndices is used to represent segmentation result.
# Simply put, ClusterPointIndices is a list of PointIndices.
Header header
pcl_msgs/PointIndices[] cluster_indices
jsk_recognition_msgs/HistogramWithRangeBin
Field:
  • min_value (float64) –
  • max_value (float64) –
  • count (uint32) –
float64 min_value
float64 max_value
uint32 count
jsk_recognition_msgs/SimpleHandle
Field:
Header header
geometry_msgs/Pose pose
float64 handle_width
jsk_recognition_msgs/SnapItRequest
Field:
Constant:
  • MODEL_PLANE (uint8):0
  • MODEL_CYLINDER (uint8):1
Header header
uint8 MODEL_PLANE=0
uint8 MODEL_CYLINDER=1
uint8 model_type

geometry_msgs/PolygonStamped target_plane

geometry_msgs/PointStamped center
geometry_msgs/Vector3Stamped direction
float64 radius
float64 height
# parameters, 0 means 
float64 max_distance
float64 eps_angle
jsk_recognition_msgs/Circle2D
Field:
  • header (std_msgs/Header) –
  • radius (float64) –
  • x (float64) –
  • y (float64) –
Header header
float64 radius
float64 x
float64 y
jsk_recognition_msgs/PolygonArray
Field:

PolygonArray is a list of PolygonStamped. You can use jsk_rviz_plugins to visualize PolygonArray on rviz.

# PolygonArray is a list of PolygonStamped.
# You can use jsk_rviz_plugins to visualize PolygonArray on rviz.
Header header
geometry_msgs/PolygonStamped[] polygons
uint32[] labels
float32[] likelihood
jsk_recognition_msgs/SparseOccupancyGridCell
Field:
  • row_index (int32) –
  • value (float32) –
int32 row_index
float32 value
jsk_recognition_msgs/Int32Stamped
Field:
Header header
int32 data
jsk_recognition_msgs/BoundingBoxMovement
Field:
Header header
BoundingBox box
geometry_msgs/Pose handle_pose
geometry_msgs/PoseStamped destination
jsk_recognition_msgs/SparseImage
Field:
  • header (std_msgs/Header) –
  • width (uint32) –
  • height (uint32) –
  • data16[] (uint16) –
  • data32[] (uint32) –
Header header

uint32 width
uint32 height

# each uint8 or uint16 contains position of white pixel expressed like: "(x << 8 or 16) ^ y"
# if max(width, height) > 256(=2^8) use data32 array, else use data16 array.
uint16[] data16
uint32[] data32
jsk_recognition_msgs/TorusArray
Field:
Header header
Torus[] toruses
jsk_recognition_msgs/RectArray
Field:
Header header
Rect[] rects
jsk_recognition_msgs/SimpleOccupancyGridArray
Field:
Header header
SimpleOccupancyGrid[] grids
jsk_recognition_msgs/SparseOccupancyGridColumn
Field:
int32 column_index
SparseOccupancyGridCell[] cells
jsk_recognition_msgs/PointsArray
Field:
Header header
sensor_msgs/PointCloud2[] cloud_list
jsk_recognition_msgs/ImageDifferenceValue
Field:
Header header

float32 difference
jsk_recognition_msgs/HistogramWithRangeArray
Field:
Header header
HistogramWithRange[] histograms
jsk_recognition_msgs/ICPResult
Field:
Header header
geometry_msgs/Pose pose
string name
float64 score
jsk_recognition_msgs/BoolStamped
Field:
Header header
bool data
jsk_recognition_msgs/ContactSensorArray
Field:
std_msgs/Header header
jsk_recognition_msgs/ContactSensor[] datas
jsk_recognition_msgs/ModelCoefficientsArray
Field:

ModelCoefficientsArray is used to represent coefficients of model for each segmented clusters. Simply put, ModelCoefficientsArray is a list of ModelCoefficients.

# ModelCoefficientsArray is used to represent coefficients of model
# for each segmented clusters.
# Simply put, ModelCoefficientsArray is a list of ModelCoefficients.
Header header
pcl_msgs/ModelCoefficients[] coefficients
jsk_recognition_msgs/HeightmapConfig
Field:
  • min_x (float32) –
  • max_x (float32) –
  • min_y (float32) –
  • max_y (float32) –
float32 min_x
float32 max_x
float32 min_y
float32 max_y
jsk_recognition_msgs/TrackerStatus
Field:
Header header
bool is_tracking
jsk_recognition_msgs/SparseOccupancyGrid
Field:
Header header
geometry_msgs/Pose origin_pose
float32 resolution

SparseOccupancyGridColumn[] columns
jsk_recognition_msgs/ContactSensor
Field:

Header

# Header
Header header

# Whether sensor detects contact or not
bool contact

string link_name
jsk_recognition_msgs/SimpleOccupancyGrid
Field:
Header header
# plane coefficients
float32[4] coefficients
# cells
float32 resolution
geometry_msgs/Point[] cells
jsk_recognition_msgs/VectorArray
Field:
Header header
int32 vector_dim
float64[] data
jsk_recognition_msgs/ClassificationResult
Field:
  • header (std_msgs/Header) –
  • labels[] (uint32) –
  • label_names[] (string) –
  • label_proba[] (float64) –
  • probabilities[] (float64) –
  • classifier (string) –
  • target_names[] (string) –

information about frame and timestamp

# information about frame and timestamp
Header header

# prediction results
uint32[] labels          # numerical labels
string[] label_names     # non-numerical labels
float64[] label_proba    # probabilities of labels
float64[] probabilities  # probabilities about each classification for all target_names

# information about classifier
string classifier        # name of classifier
string[] target_names    # set in which label_names should be
jsk_recognition_msgs/ColorHistogram
Field:
Header header
float32[] histogram
jsk_recognition_msgs/TimeRange
Field:

Represents range of time.

# Represents range of time.
std_msgs/Header header
time start
time end
jsk_recognition_msgs/PlotDataArray
Field:
Header header
jsk_recognition_msgs/PlotData[] data
bool no_legend
float32 legend_font_size
float32 max_x
float32 min_x
float32 min_y
float32 max_y
jsk_recognition_msgs/ParallelEdge
Field:
Header header
pcl_msgs/PointIndices[] cluster_indices
pcl_msgs/ModelCoefficients[] coefficients
jsk_recognition_msgs/SparseOccupancyGridArray
Field:
Header header
SparseOccupancyGrid[] grids
jsk_recognition_msgs/DepthCalibrationParameter
Field:
  • coefficients2[] (float64) –
  • coefficients1[] (float64) –
  • coefficients0[] (float64) –
  • use_abs (bool) –

each vector stands for C(u, v) C(u, v) = a_0 * u^2 + a_1 * u + a_2 * v^2 + a_3 * v + a_4

# each vector stands for C(u, v)
# C(u, v) = a_0 * u^2 + a_1 * u + a_2 * v^2 + a_3 * v + a_4
float64[] coefficients2
float64[] coefficients1
float64[] coefficients0
bool use_abs
jsk_recognition_msgs/Circle2DArray
Field:
Header header
Circle2D[] circles
jsk_recognition_msgs/ParallelEdgeArray
Field:
Header header
ParallelEdge[] edge_groups
jsk_recognition_msgs/BoundingBox
Field:

BoundingBox represents a oriented bounding box.

# BoundingBox represents a oriented bounding box.
Header header
geometry_msgs/Pose pose
geometry_msgs/Vector3 dimensions  # size of bounding box (x, y, z)
# You can use this field to hold value such as likelihood
float32 value
uint32 label
jsk_recognition_msgs/DepthErrorResult
Field:
  • header (std_msgs/Header) –
  • u (uint32) –
  • v (uint32) –
  • center_u (float32) –
  • center_v (float32) –
  • true_depth (float32) –
  • observed_depth (float32) –
Header header
uint32 u
uint32 v
float32 center_u
float32 center_v
float32 true_depth
float32 observed_depth
jsk_recognition_msgs/HistogramWithRange
Field:
Header header
HistogramWithRangeBin[] bins
jsk_recognition_msgs/PosedCameraInfo
Field:
Header header
sensor_msgs/CameraInfo camera_info
geometry_msgs/Pose offset
jsk_recognition_msgs/RotatedRect
Field:
  • x (float64) –
  • y (float64) –
  • width (float64) –
  • height (float64) –
  • angle (float64) –
float64 x
float64 y
float64 width
float64 height
float64 angle # degree
jsk_recognition_msgs/PlotData
Constant:
  • SCATTER (uint32):1
  • LINE (uint32):2
Field:
  • header (std_msgs/Header) –
  • xs[] (float32) –
  • ys[] (float32) –
  • type (uint32) –
  • label (string) –
  • fit_line (bool) –
  • fit_line_ransac (bool) –
uint32 SCATTER=1
uint32 LINE=2

Header header
float32[] xs
float32[] ys
uint32 type                     #SCATTER or LINE
string label
bool fit_line
bool fit_line_ransac

Service types

jsk_recognition_msgs/SetPointCloud2
Field (Request):
 
Field (Response):
 
  • output (string) –
sensor_msgs/PointCloud2 cloud
string name
---
string output