openraveros/robot_sensorgetdata Service

File: openraveros/robot_sensorgetdata.srv

Raw Message Definition

# Gets the sensor data. The format returned is dependent on the type of sensor. 

int32 robotid
uint32 sensorindex
---

# data.type - contains the id of the data type (see SensorBase::SensorType)
string type

## laser

#  data.laserrange - 3xN array where each column is the direction * distance
float32[] laserrange

#  data.laserpos - 3xN array where each column is the corresponding origin of each range measurement
float32[] laserpos

#  data.laserint - 1xN optional laser intensity array
float32[] laserint

## camera
sensor_msgs/CameraInfo caminfo # camera calibration parameters and where camera is
sensor_msgs/Image camimage # camera image

Compact Message Definition

int32 robotid
uint32 sensorindex

string type
float32[] laserrange
float32[] laserpos
float32[] laserint
sensor_msgs/CameraInfo caminfo
sensor_msgs/Image camimage