Skip to content

Commit

Permalink
copy latest changes from dev branch to release branch
Browse files Browse the repository at this point in the history
  • Loading branch information
desengph committed Nov 11, 2021
2 parents 7fd999b + b3a224c commit 84a2843
Show file tree
Hide file tree
Showing 14 changed files with 81 additions and 199 deletions.
2 changes: 1 addition & 1 deletion ifm3d_ros_driver/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@ find_package(catkin REQUIRED COMPONENTS
ifm3d_ros_msgs
)

catkin_python_setup()
# catkin_python_setup()

option(CATKIN_ENABLE_TESTING "Build tests" OFF)

Expand Down
227 changes: 53 additions & 174 deletions ifm3d_ros_driver/doc/dump_and_config.md
Original file line number Diff line number Diff line change
Expand Up @@ -18,187 +18,63 @@ Per camera head connected to the visual processing unit (VPU) of the O3R platfor

As you can see the two services `Dump` and `Config` are also part of this list.
### Dump
Call this service via, e.g. for camera1:
Calling the native rosservice `/ifm3d_ros_examples/camera/Dump` for a certain `camera` will return a string containing with the camera configuration as a JSON string. Please notice the use of backslashes (`\` before each `"`) to esacpe each upper quotation mark. This is necessary to allow us to keep the JSON syntax native to the underlying API (ifm3d).

>Note: We have mapped some camera configurations to native rosservice calls to make their handling easier, e.g. `rosservice call /ifm3d_ros_examples/camera/SoftOn`. If you think you will benefit from similar rosservices, please let us know so we can add more comfort handling.
Call this service via, e.g. for camera:
```
$ rosservice call /ifm3d_ros_examples/camera1/Dump
$ rosservice call /ifm3d_ros_examples/camera/Dump
status: 0
{
"device": {
"clock": {
"currentTime": 1581193835185485800
},
"diagnostic": {
"temperatures": [],
"upTime": 103190000000000
},
"info": {
"device": "0301",
"deviceTreeBinaryBlob": "tegra186-quill-p3310-1000-c03-00-base.dtb",
"features": {},
"name": "",
" partNumber": "M03975",
"productionState": "AA",
"serialNumber": "000201234160",
"vendor": "0001"
},
"network": {
"authorized_keys": "",
"ipAddressConfig": 0,
"macEth0": "00:04:4B:EA:9F:0E",
"macEth1": "00:02:01:23:41:60",
"networkSpeed": 1000,
"staticIPv4Address": "192.168.0.69",
"staticIPv4Gateway": "192.168.0.201",
"staticIPv4SubNetMask": "255.255.255.0",
"useDHCP": false
},
"state": {
"errorMessage": "",
"errorNumber": ""
},
"swVersion": {
"kernel": "4.9.140-l4t-r32.4+gc35f5eb9d1d9",
"l4t": "r32.4.3",
"os": "0.13.13-221",
"schema": "v0.1.0",
"swu": "0.15.12"
}
},
"ports": {
"port0": {
"acquisition": {
"framerate": 10,
"version": {
"major": 0,
"minor": 0,
"patch": 0
}
},
"data": {
"algoDebugConfig": {},
"availablePCICOutput": [],
"pcicTCPPort": 50010
},
"info": {
"device": "2301",
"deviceTreeBinaryBlobOverlay": "001-ov9782.dtbo",
"features": {
"fov": {
"horizontal": 127,
"vertical": 80
},
" resolution": {
"height": 800,
"width": 1280
},
"type": "2D"
},
"name": "",
"partNumber": "M03969",
"productionState": "AA",
"sensor": "OV9782",
"sensorID": "OV9782_127x80_noIllu_Csample",
"serialNumber": "000000000382",
"vendor": "0001"
},
"mode": "experimental_autoexposure2D",
"processing": {
"extrinsicHeadToUser": {
"rotX": 0,
"rotY": 0,
"rotZ": 0,
" transX": 0,
"transY": 0,
"transZ": 0
},
"version": {
"major": 0,
"minor": 0,
" patch": 0
}
},
"state": "RUN"
},
"port2": {
"acquisition": {
"exposureLong": 5000,
" exposureShort": 400,
"framerate": 10,
"offset": 0,
"version": {
"major": 0,
" minor": 0,
"patch": 0
}
},
"data": {
"algoDebugConfig": {},
"availablePCICOutput": [],
"pcicTCPPort": 50012
},
"info": {
"device": "3101",
"deviceTreeBinaryBlobOverlay": "001-irs2381c.dtbo",
"features": {
"fov": {
"horizontal": 105,
"vertical": 78
},
" resolution": {
"height": 172,
"width": 224
},
"type": "3D"
},
"name": "",
"partNumber": "M03969",
"productionState": "AA",
"sensor": "IRS2381C",
"sensorID": "IRS2381C_105x78_4x2W_110x90_C7",
"serialNumber": "000000000382",
"vendor": "0001"
},
"mode": "standard_range4m",
"processing": {
"diParam": {
"anfFilterSizeDiv2": 2,
"enableDynamicSymmetry": true,
"enableStraylight": true,
"enableTemporalFilter": true,
"excessiveCorrectionThreshAmp": 0.3,
"excessiveCorrectionThreshDist": 0.08,
"maxDistNoise": 0.02,
"maxSymmetry": 0.4,
"medianSizeDiv2": 0,
"minAmplitude": 20,
"minReflectivity": 0,
"mixedPixelFilterMode": 1,
"mixedPixelThresholdRad": 0.15
},
"extrinsicHeadToUser": {
"rotX": 1,
"rotY": 0,
"rotZ": 0,
"transX": 100,
"transY": 0,
"transZ": 0
},
"version": {
" major": 0,
"minor": 0,
"patch": 0
}
},
"state": "RUN"
}
}
}
config: "{\"device\":{\"clock\":{\"currentTime\":1581287336449588512},\"diagnostic\":{\"temperatures\"\
:[],\"upTime\":196692000000000},\"info\":{\"device\":\"0301\",\"deviceTreeBinaryBlob\"\
:\"tegra186-quill-p3310-1000-c03-00-base.dtb\",\"features\":{},\"name\":\"test\"\
,\"partNumber\":\"M03975\",\"productionState\":\"AA\",\"serialNumber\":\"000201234160\"\
,\"vendor\":\"0001\"},\"network\":{\"authorized_keys\":\"\",\"ipAddressConfig\"\
:0,\"macEth0\":\"00:04:4B:EA:9F:0E\",\"macEth1\":\"00:02:01:23:41:60\",\"networkSpeed\"\
:1000,\"staticIPv4Address\":\"192.168.0.69\",\"staticIPv4Gateway\":\"192.168.0.201\"\
,\"staticIPv4SubNetMask\":\"255.255.255.0\",\"useDHCP\":false},\"state\":{\"errorMessage\"\
:\"\",\"errorNumber\":\"\"},\"swVersion\":{\"kernel\":\"4.9.140-l4t-r32.4+gc35f5eb9d1d9\"\
,\"l4t\":\"r32.4.3\",\"os\":\"0.13.13-221\",\"schema\":\"v0.1.0\",\"swu\":\"0.15.12\"\
}},\"ports\":{\"port0\":{\"acquisition\":{\"framerate\":10.0,\"version\":{\"major\"\
:0,\"minor\":0,\"patch\":0}},\"data\":{\"algoDebugConfig\":{},\"availablePCICOutput\"\
:[],\"pcicTCPPort\":50010},\"info\":{\"device\":\"2301\",\"deviceTreeBinaryBlobOverlay\"\
:\"001-ov9782.dtbo\",\"features\":{\"fov\":{\"horizontal\":127,\"vertical\":80},\"\
resolution\":{\"height\":800,\"width\":1280},\"type\":\"2D\"},\"name\":\"\",\"partNumber\"\
:\"M03969\",\"productionState\":\"AA\",\"sensor\":\"OV9782\",\"sensorID\":\"OV9782_127x80_noIllu_Csample\"\
,\"serialNumber\":\"000000000382\",\"vendor\":\"0001\"},\"mode\":\"experimental_autoexposure2D\"\
,\"processing\":{\"extrinsicHeadToUser\":{\"rotX\":0.0,\"rotY\":0.0,\"rotZ\":0.0,\"\
transX\":0.0,\"transY\":0.0,\"transZ\":0.0},\"version\":{\"major\":0,\"minor\":0,\"\
patch\":0}},\"state\":\"RUN\"},\"port2\":{\"acquisition\":{\"exposureLong\":5000,\"\
exposureShort\":400,\"framerate\":10.0,\"offset\":0.0,\"version\":{\"major\":0,\"\
minor\":0,\"patch\":0}},\"data\":{\"algoDebugConfig\":{},\"availablePCICOutput\"\
:[],\"pcicTCPPort\":50012},\"info\":{\"device\":\"3101\",\"deviceTreeBinaryBlobOverlay\"\
:\"001-irs2381c.dtbo\",\"features\":{\"fov\":{\"horizontal\":105,\"vertical\":78},\"\
resolution\":{\"height\":172,\"width\":224},\"type\":\"3D\"},\"name\":\"\",\"partNumber\"\
:\"M03969\",\"productionState\":\"AA\",\"sensor\":\"IRS2381C\",\"sensorID\":\"IRS2381C_105x78_4x2W_110x90_C7\"\
,\"serialNumber\":\"000000000382\",\"vendor\":\"0001\"},\"mode\":\"standard_range2m\"\
,\"processing\":{\"diParam\":{\"anfFilterSizeDiv2\":2,\"enableDynamicSymmetry\"\
:true,\"enableStraylight\":true,\"enableTemporalFilter\":true,\"excessiveCorrectionThreshAmp\"\
:0.3,\"excessiveCorrectionThreshDist\":0.08,\"maxDistNoise\":0.02,\"maxSymmetry\"\
:0.4,\"medianSizeDiv2\":0,\"minAmplitude\":20.0,\"minReflectivity\":0.0,\"mixedPixelFilterMode\"\
:1,\"mixedPixelThresholdRad\":0.15},\"extrinsicHeadToUser\":{\"rotX\":0.0,\"rotY\"\
:0.0,\"rotZ\":0.0,\"transX\":0.0,\"transY\":0.0,\"transZ\":0.0},\"version\":{\"\
major\":0,\"minor\":0,\"patch\":0}},\"state\":\"RUN\"}}}"
```
## Config
Below you can see an example on how to configure your camera via a rosservice call. The JSON string can be a partial JSON string. It only needs to follow basic JSON syntax.

```
rosservice call /ifm3d_ros_examples/camera2/Config "json: '{"ports": {"port2": {"state": "RUN"}}}'"
$ rosservice call /ifm3d_ros_examples/camera/Config "json: '{\"ports\":{\"port2\":{\"mode\":\"standard_range2m\"}}}'"
status: 0
msg: "OK"
```

This is equivalent to:
```
$ rosservice call /ifm3d_ros_examples/camera/Config '"{\"ports\":{\"port2\":{\"mode\":\"standard_range2m\"}}}"'
status: 0
msg: "OK"
```

Expand All @@ -211,7 +87,10 @@ They are part of the `ifm3d_ros_msgs` subpackage, so if you can't access them pl
For example, to dump the state of the camera:
(exemplary output from an O3R perception platform with one camera head connected is shown)

>Note: The service proxying only works on the `/ifm3d_ros_examples/camera/` namespace at the moment.
```
$ roslaunch ifm3d_ros_examples camera.launch &
$ rosrun ifm3d_ros_msgs dump
{
"device": {
Expand Down
Binary file not shown.
Binary file not shown.
2 changes: 1 addition & 1 deletion ifm3d_ros_driver/src/camera_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -183,7 +183,7 @@ bool ifm3d_ros::CameraNodelet::Config(ifm3d_ros_msgs::Config::Request& req, ifm3

try
{
this->cam_->FromJSON(req.json);
this->cam_->FromJSON(json::parse(req.json));
}
catch (const ifm3d::error_t& ex)
{
Expand Down
2 changes: 1 addition & 1 deletion ifm3d_ros_examples/launch/four_cameras.launch
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<?xml version="1.0"?>
<launch>
<!-- This lauch file is an example for how to use four camera heads at the same time: their data will be transformed into a collective reference frame witout any relative calibration in 3D. -->
<!-- This lauch file is an example for how to use four camera heads at the same time: their data will be transformed into a collective reference frame without any relative calibration in 3D. -->

<!-- Command-line arguments -->
<arg name="namespace" default="ifm3d_ros_examples" doc="Desired namespace for the camera nodelet" />
Expand Down
30 changes: 16 additions & 14 deletions ifm3d_ros_examples/launch/six_cameras.launch
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,8 @@
<arg name="nodelet_name2" default="camera2"/>
<arg name="nodelet_name3" default="camera3"/>
<arg name="nodelet_name4" default="camera4"/>
<arg name="nodelet_name5" default="camera5"/>
<arg name="nodelet_name6" default="camera6"/>
<arg name="ip" default="192.168.0.69" doc="The IP address of the VPU, i.e. main processing unit." />
<arg name="xmlrpc_port" default="80" doc="The TCP port the camera's xmlrpc server is listening on for requests."/>
<arg name="pcic_port_1" default="50010" doc="The TCP (data) port the first camera's pcic server is listening on for requests."/>
Expand Down Expand Up @@ -86,7 +88,7 @@

<!-- node 5 -->
<include ns="$(arg namespace)" file="$(find ifm3d_ros_examples)/launch/nodelet.launch">
<arg name="camera" value="$(arg nodelet_name4)"/>
<arg name="camera" value="$(arg nodelet_name5)"/>
<arg name="ip" value="$(arg ip)"/>
<arg name="xmlrpc_port" value="$(arg xmlrpc_port)"/>
<arg name="pcic_port" value="$(arg pcic_port_5)"/>
Expand All @@ -101,7 +103,7 @@

<!-- node 6 -->
<include ns="$(arg namespace)" file="$(find ifm3d_ros_examples)/launch/nodelet.launch">
<arg name="camera" value="$(arg nodelet_name4)"/>
<arg name="camera" value="$(arg nodelet_name6)"/>
<arg name="ip" value="$(arg ip)"/>
<arg name="xmlrpc_port" value="$(arg xmlrpc_port)"/>
<arg name="pcic_port" value="$(arg pcic_port_6)"/>
Expand All @@ -117,38 +119,38 @@
<!-- coord frame transform from ROS sensor frame to static map frame (no egomotion) -->
<node pkg="tf2_ros"
type="static_transform_publisher"
name="$(arg nn1)_tf"
args="0 0 0 0 0 0 map $(arg ns)/$(arg nn1)_link"
name="$(arg nodelet_name1)_tf"
args="0 0 0 0 0 0 map $(arg namespace)/$(arg nodelet_name1)_link"
respawn="$(arg respawn)" />

<node pkg="tf2_ros"
type="static_transform_publisher"
name="$(arg nn2)_tf"
args="0 0 0 0 0 0 map $(arg ns)/$(arg nn2)_link"
name="$(arg nodelet_name2)_tf"
args="0 0 0 0 0 0 map $(arg namespace)/$(arg nodelet_name2)_link"
respawn="$(arg respawn)" />

<node pkg="tf2_ros"
type="static_transform_publisher"
name="$(arg nn3)_tf"
args="0 0 0 0 0 0 map $(arg ns)/$(arg nn3)_link"
name="$(arg nodelet_name3)_tf"
args="0 0 0 0 0 0 map $(arg namespace)/$(arg nodelet_name3)_link"
respawn="$(arg respawn)" />

<node pkg="tf2_ros"
type="static_transform_publisher"
name="$(arg nn4)_tf"
args="0 0 0 0 0 0 map $(arg ns)/$(arg nn4)_link"
name="$(arg nodelet_name4)_tf"
args="0 0 0 0 0 0 map $(arg namespace)/$(arg nodelet_name4)_link"
respawn="$(arg respawn)" />

<node pkg="tf2_ros"
type="static_transform_publisher"
name="$(arg nn5)_tf"
args="0 0 0 0 0 0 map $(arg ns)/$(arg nn5)_link"
name="$(arg nodelet_name5)_tf"
args="0 0 0 0 0 0 map $(arg namespace)/$(arg nodelet_name5)_link"
respawn="$(arg respawn)" />

<node pkg="tf2_ros"
type="static_transform_publisher"
name="$(arg nn6)_tf"
args="0 0 0 0 0 0 map $(arg ns)/$(arg nn6)_link"
name="$(arg nodelet_name6)_tf"
args="0 0 0 0 0 0 map $(arg namespace)/$(arg nodelet_name6)_link"
respawn="$(arg respawn)" />

</launch>
1 change: 1 addition & 0 deletions ifm3d_ros_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@ find_package(catkin REQUIRED COMPONENTS
#######################################
## Declare ROS messages and services ##
#######################################
catkin_python_setup()

add_message_files(
DIRECTORY msg
Expand Down
2 changes: 1 addition & 1 deletion ifm3d_ros_msgs/bin/config
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@


import sys
from ifm3d import ConfigClient
from ifm3d_ros_utils import ConfigClient

if __name__ == '__main__':
sys.exit(ConfigClient().run())
2 changes: 1 addition & 1 deletion ifm3d_ros_msgs/bin/dump
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@


import sys
from ifm3d import DumpClient
from ifm3d_ros_utils import DumpClient

if __name__ == '__main__':
sys.exit(DumpClient().run())
4 changes: 2 additions & 2 deletions ifm3d_ros_driver/setup.py → ifm3d_ros_msgs/setup.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,8 +3,8 @@

# reads package.xml
setup_args = generate_distutils_setup(
packages=['ifm3d'],
package_dir={'': 'pylib'},
packages=['ifm3d_ros_utils'],
package_dir={'': 'utils'},
)

setup(**setup_args)
Loading

0 comments on commit 84a2843

Please sign in to comment.