Sensor-ext
note
This is a special resource to control sensors in SENSR. You can add, delete or modify sensors via this resource.
GET
/[SENSR version]/settings/sensor-ext/list
Get the list of available config-id and config data type of a specific type of sensor.
- Parameters
- sensor-type : The type of sensor(
lidar
/odom
/can
)
- sensor-type : The type of sensor(
- Return code
- 200 OK
- 404 NOT FOUND
Example
$ curl -X GET 'http://localhost:9080/[SENSR version]/settings/sensor-ext/list?sensor-type=lidar'
** Respond **
[
{
"uid": "String",
"name": "String",
"topic": "String",
"sensor": "String",
"stack_capacity": "Int",
"detection_radius": "Float",
"horizontal_angle_range": "Vector2",
"use_intensity_filtering": "Bool",
"use_lidar_timestamp": "Bool",
"use_corrected_pose": "Bool",
"save_corrected_pose": "Bool",
"disabled": "Bool",
"minimum_intensity": "Float",
"retro_reflective_intensity": "Float",
"arguments": "Table",
"connected_to_edge_node": "Bool",
"edge_uid": "String",
"base_to_origin": {
"tx": "Float",
"ty": "Float"
},
"sensor_to_base": {
"tz": "Float",
"qw": "Float",
"qx": "Float",
"qy": "Float",
"qz": "Float"
},
"pose_correction": {
"tx": "Float",
"ty": "Float",
"tz": "Float",
"qw": "Float",
"qx": "Float",
"qy": "Float",
"qz": "Float"
}
}
]
/[SENSR version]/settings/sensor-ext
Get an actual configuration settings of the desired sensor.
If you do not pass any
sensor-id
, this command returns the full sensor IDs in SENSR. You can filter this list by passing innode-uri
to filter out only the sensors beloning to a specified algo node.- Parameters
- sensor-id : ID of sensor.
- node-uri (optional) : ID of algo node.
- Return code
- 200 OK
- 400 BAD REQ
Example
$ curl -X GET 'http://localhost:9080/[SENSR version]/settings/sensor-ext?sensor-id=lidar_0000'
** Respond **
{
"uid": "lidar_0000",
"name": "ROS Message",
"topic": "/lidar_0001/pandar",
"sensor": "ROS Message",
"connected_to_edge_node": false,
"edge_uid": "",
"stack_capacity": 0,
"detection_radius": 1000,
"horizontal_angle_range": [
-180,
180
],
"use_lidar_timestamp": false,
"use_corrected_pose": false,
"save_corrected_pose": true,
"use_intensity_filtering": false,
"disabled": false,
"minimum_intensity": 0,
"retro_reflective_intensity": 255,
"base_to_origin": {
"tx": -12.603933334350586,
"ty": -6.328624725341797
},
"sensor_to_base": {
"tz": 4.517395496368408,
"qw": -0.130505308508873,
"qx": 0.07877259701490402,
"qy": 0.04761473089456558,
"qz": 0.9871656894683838
},
"pose_correction": {
"tx": 0,
"ty": 0,
"tz": 0,
"qw": 0,
"qx": 0,
"qy": 0,
"qz": 0
},
"arguments":{}
}
$ curl -X GET 'http://localhost:9080/[SENSR version]/settings/sensor-ext'
** Respond **
[
"lidar_0000",
"lidar_0001"
]
$ curl -X GET 'http://localhost:9080/[SENSR version]/settings/sensor-ext?node-uri=algo_0000'
** Respond **
[
"lidar_0000"
]
PUT
/[SENSR version]/settings/sensor-ext
Add a new sensor to the desired algo node. If this command was successful the ID of the newly added sensor is returned.
You should pass in the sensor data with this PUT command via the request body.
You should also call /commands/apply-change to apply and save your changes. Without this the changes will not properly take effect in SENSR.
List of valid sensor
- "ROS Message"
- "Velodyne 16"
- "Velodyne 32"
- "Velodyne 64"
- "Velodyne 128"
- "Velodyne HDL-32"
- "Hesai 20A"
- "Hesai 20B"
- "Hesai 40P"
- "Hesai 40M"
- "Hesai XT-16"
- "Hesai XT-32"
- "Hesai QT"
- "Hesai 64"
- "Livox"
- "Innoviz Pro" // X86_64 only
- "Innoviz One" // X86_64 only
- "Ouster-OS"
- "Baraja"
- "Cepton Vista"
- "Quanergy"
- "Quanergy MQ-8"
- "Blickfeld Cube 1"
- "Blickfeld Cube Range 1"
- "Luminar Hydra"
- "Innovusion Falcon"
- "AEye 4Sight M"
- Parameters
- node-uri : ID of the desired algo node.
- sensor-type : The type of sensor (
lidar
/odom
/can
)
- Return code
- 200 OK
- 400 BAD REQ
Example
$ curl -X PUT 'http://localhost:9080/[SENSR version]/settings/sensor-ext?node-uri=algo_0000&sensor-type=lidar'
--data '{
"name": "PointCloud",
"topic": "/velodyne_points",
"sensor": "ROS Message",
"stack_capacity": 0,
"detection_radius": 1000.0,
"horizontal_angle_range": [-180.0, 180.0],
"use_lidar_timestamp" : false,
"use_intensity_filtering" : false,
"use_corrected_pose":false,
"save_corrected_pose":false,
"minimum_intensity": 0.0,
"retro_reflective_intensity": 200.0,
"connected_to_edge_node": false,
"edge_uid":"",
"base_to_origin": {
"tx": 0.0,
"ty": 0.0
},
"sensor_to_base": {
"tz": 0.0,
"qw": 1.0,
"qx": 0.0,
"qy": 0.0,
"qz": 0.0
},
"pose_correction": {
"tx": 0.0,
"ty": 0.0,
"tz": 0.0,
"qw": 0.0,
"qx": 0.0,
"qy": 0.0,
"qz": 0.0
},
"disabled": false,
"arguments": {}
}'
** Respond **
"lidar_0001"
POST
/[SENSR version]/settings/sensor-ext
Update the config of the desired sensor. Note that
topic
should be unique within an algo node.See the PUT section for the list of valid sensors.
You should also call /commands/apply-change to apply your changes.
- Parameters
- N/A
- Return code
- 200 OK
- 400 BAD REQ
- Example
$ curl -X POST 'http://localhost:9080/[SENSR version]/settings/sensor-ext'
--data '{
"name": "PointCloud",
"topic": "/velodyne_points",
"sensor": "ROS Message",
"stack_capacity": 0,
"detection_radius": 1000.0,
"horizontal_angle_range": [-180.0, 180.0],
"use_lidar_timestamp" : false,
"use_intensity_filtering" : false,
"use_corrected_pose":false,
"save_corrected_pose":false,
"minimum_intensity": 0.0,
"retro_reflective_intensity": 200.0,
"connected_to_edge_node": false,
"edge_uid":"",
"base_to_origin": {
"tx": 0.0,
"ty": 0.0
},
"sensor_to_base": {
"tz": 0.0,
"qw": 1.0,
"qx": 0.0,
"qy": 0.0,
"qz": 0.0
},
"pose_correction": {
"tx": 0.0,
"ty": 0.0,
"tz": 0.0,
"qw": 0.0,
"qx": 0.0,
"qy": 0.0,
"qz": 0.0,
},
"disabled": false,
"arguments": {}
}'
** Respond **
200 OK
DELETE
/[SENSR version]/settings/sensor-ext
Delete a sensor.
- Parameters
- sensor-id : ID of sensor.
- Return code
- 200 OK
- 400 BAD REQ
Example
$ curl -X DELETE 'http://localhost:9080/[SENSR version]/settings/sensor-ext?sensor-id=lidar_0001'
** Respond **
200 OK