-
Notifications
You must be signed in to change notification settings - Fork 11
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Merge pull request #16 from PepperlFuchs/feature/pfsdp_services
Feature/pfsdp services
- Loading branch information
Showing
36 changed files
with
833 additions
and
496 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,109 @@ | ||
## ROS Services | ||
|
||
The ROS driver provides the following services. They use the sensor specific Pepperl+Fuchs scan data | ||
protocol (PFSDP - [R2000](https://files.pepperl-fuchs.com/webcat/navi/productInfo/doct/doct3469g.pdf) / | ||
[R2300](https://files.pepperl-fuchs.com/webcat/navi/productInfo/doct/doct7001b.pdf)) which is a simple | ||
command protocol using HTTP requests and responses. Please see the following detailed descriptions and | ||
examples to call these services. The examples are based on the assumption that the node name is pf_r2000. | ||
Which parameters can be written with which values can be found in the PFSDP documents (R2x00 Ethernet | ||
communication protocol) linked above. | ||
|
||
**List parameters** | ||
The service pfsdp_list_parameters returns a list of all available global sensor parameters. | ||
``` | ||
ros2 service call /pf_r2000/pfsdp_list_parameters pf_interfaces/srv/PfsdpListParameters | ||
``` | ||
|
||
**Get parameter** | ||
The service pfsdp_get_parameter reads the current value of one global sensor parameters. | ||
``` | ||
ros2 service call /pf_r2000/pfsdp_get_parameter pf_interfaces/srv/PfsdpGetParameter '{name: user_tag}' | ||
``` | ||
|
||
**Set parameter** | ||
Using the service pfsdp_set_parameter the value of any write-accessible global sensor parameter can | ||
be changed. | ||
``` | ||
ros2 service call /pf_r2000/pfsdp_set_parameter pf_interfaces/srv/PfsdpSetParameter '{name: user_tag, value: test123}' | ||
``` | ||
|
||
**Reset parameter** | ||
The service pfsdp_reset_parameter resets one global sensor parameter to the factory default value. | ||
``` | ||
ros2 service call /pf_r2000/pfsdp_reset_parameter pf_interfaces/srv/PfsdpResetParameter '{name: user_tag}' | ||
``` | ||
|
||
**List I/Q parameters** | ||
The service pfsdp_list_iq_parameters is similar to the generic list parameters service but returns | ||
all parameters related to the switching input/output channels I/Qn. | ||
``` | ||
ros2 service call /pf_r2000/pfsdp_list_iq_parameters pf_interfaces/srv/PfsdpListIqParameters | ||
``` | ||
|
||
**Get I/Q parameter** | ||
The service pfsdp_get_iq_parameter is similar to the generic pfsdp_get_parameter service but operates | ||
on parameters related to the switching input/output channels I/Qn. The service returns the current | ||
value of one parameter. | ||
``` | ||
ros2 service call /pf_r2000/pfsdp_get_iq_parameter pf_interfaces/srv/PfsdpGetIqParameter '{name: iq2_polarity}' | ||
``` | ||
|
||
**Set I/Q parameter** | ||
The service pfsdp_set_iq_parameter is similar to the generic pfsdp_set_parameter service but operates | ||
on parameters related to the switching input/output channels I/Qn. Using the service pfsdp_set_iq_parameter | ||
the value of any write-accessible I/Q parameter can be modified. | ||
``` | ||
ros2 service call /pf_r2000/pfsdp_set_iq_parameter pf_interfaces/srv/PfsdpSetIqParameter '{name: iq2_polarity, value: active_low}' | ||
``` | ||
|
||
**Get protocol info** | ||
The service pfsdp_get_protocol_info returns basic version information on the communication protocol. | ||
``` | ||
ros2 service call /pf_r2000/pfsdp_get_protocol_info pf_interfaces/srv/PfsdpGetProtocolInfo | ||
``` | ||
|
||
**Reboot device** | ||
The service pfsdp_reboot_device triggers a soft reboot of the sensor firmware. | ||
``` | ||
ros2 service call /pf_r2000/pfsdp_reboot_device pf_interfaces/srv/PfsdpRebootDevice | ||
``` | ||
|
||
**Factory reset** | ||
The service pfsdp_factory_reset performs a complete reset of all sensor settings to factory defaults | ||
and reboots the device. | ||
``` | ||
ros2 service call /pf_r2000/pfsdp_factory_reset pf_interfaces/srv/PfsdpFactoryReset | ||
``` | ||
|
||
## Service type and interface: | ||
The service type determines which data is used for the request and response of a service. The following command is an | ||
example for determining the type of the pfsdp_set_parameter service: | ||
``` | ||
ros2 service type /pf_r2000/pfsdp_set_parameter | ||
``` | ||
The return should be the following. Which is also the path to the file where the request and response data is described in detail: | ||
``` | ||
pf_interfaces/srv/PfsdpSetParameter | ||
``` | ||
To show the request and response interface/data for the pfsdp_set_parameter service the following command can be used: | ||
``` | ||
ros2 interface show pf_interfaces/srv/PfsdpSetParameter | ||
``` | ||
The return should be the following and shows the data name and type of the request above and of the response below the three dashes. | ||
``` | ||
string name | ||
string value | ||
- - - | ||
int32 error_code | ||
string error_text | ||
``` | ||
|
||
## Service execution status | ||
All previously described services return at least the error code (error_code) and error text (error_text) in the response. | ||
Both contain the status of the service execution. Error codes (data type int32) not equal to 0 indicate an error during service | ||
execution. Error text (data type string) shows the status of the service execution as a description readable by humans. | ||
Exemplary the following response of the service pfsdp_get_parameter shows the error code, error text and as first return value | ||
the read parameter vendor. | ||
``` | ||
pf_interfaces.srv.PfsdpGetParameter_Response(value='Pepperl+Fuchs', error_code=0, error_text='success') | ||
``` |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,117 @@ | ||
## ROS Topics | ||
|
||
**R2000 & R2300 1-layer:** | ||
|
||
| Topic | Type | Description | | ||
| ------------- | ------------- | ---------------------------------------------------------------------------------------------------------------------------- | | ||
| /pf/scan | LaserScan | ROS standard message, see [sensor_msgs/LaserScan](https://docs.ros.org/en/jazzy/p/sensor_msgs/interfaces/msg/LaserScan.html) | | ||
| /r2000_header | PFR2000Header | Sensor specific message, see [pf_interfaces/msg/PFR2000Header.msg](../src/pf_interfaces/msg/PFR2000Header.msg) | | ||
|
||
Topic PFR2000Header details: | ||
|
||
| Type | Name | Description | | ||
| ------ | ----------------- | ------------------------------------------------------------------------------------------------------------------------- | | ||
| uint16 | magic | magic byte (0xa25c) marking the beginning of a packet | | ||
| uint16 | packet_type | scan data packet type (0x0041 - 'A' 0x0042 - 'B' 0x0043 - 'C') | | ||
| uint32 | packet_size | overall packet size in bytes (header + payload) | | ||
| uint16 | header_size | header size in bytes (offset to payload data) | | ||
| uint16 | scan_number | sequence number for scan (incremented for every scan, starting with 0, overflows) | | ||
| uint16 | packet_number | sequence number for packet (counting packets of a particular scan, starting with 1) | | ||
| | | | | ||
| uint64 | timestamp_raw | raw timestamp of first scan point in this packet in NTP time format | | ||
| uint64 | timestamp_sync | synchronized timestamp of first scan point in this packet in NTP time format (currenty not available and and set to zero) | | ||
| uint32 | status_flags | scan status flags | | ||
| uint32 | scan_frequency | frequency of head rotation (1/1000Hz) | | ||
| uint16 | num_points_scan | number of scan points (samples) within complete scan | | ||
| uint16 | num_points_packet | total number of scan points within this packet | | ||
| uint16 | first_index | index of first scan point within this packet | | ||
| int32 | first_angle | absolute angle of first scan point within this packet (1/10000°) | | ||
| int32 | angular_increment | delta between two succeding scan points (1/10000°) CCW rotation: +ve, CW rotation: -ve | | ||
| uint32 | iq_input | reserved - all bits zero for devices without switching I/Q | | ||
| uint32 | iq_overload | reserved - all bits zero for devices without switching I/Q | | ||
| uint64 | iq_timestamp_raw | raw timestamp for status of switching I/Q | | ||
| uint64 | iq_timestamp_sync | synchronized timestamp for status of switching I/Q | | ||
|
||
status_flags details: | ||
|
||
| Bit | Flag name | Description | | ||
| --------------- |--------------------------- | --------------------------------------------------------------------------------- | | ||
| *Informational* | | | | ||
| 0 | scan_data_info | Accumulative flag – set if any informational flag (bits 1..7) is set | | ||
| 1 | new_settings | System settings for scan data acquisition changed during recording of this packet | | ||
| 2 | invalid_data | Consistency of scan data is not guaranteed for this packet | | ||
| 3 | unstable_rotation | Scan frequency did not match set value while recording this scan data packet | | ||
| 4 | skipped_packets | Preceding scan data packets have been skipped due to connection issues | | ||
| *Warnings* | | | | ||
| 8 | device_warning | Accumulative flag – set if any warning flag (bits 9..15) is set | | ||
| 9 | lens_contamination_warning | LCM warning threshold triggered for at least one sector | | ||
| 10 | low_temperature_warning | Current internal temperature below warning threshold | | ||
| 11 | high_temperature_warning | Current internal temperature above warning threshold | | ||
| 12 | device_overload | Overload warning – sensor CPU overload is imminent | | ||
| *Errors* | | | | ||
| 16 | device_error | Accumulative flag – set if any error flag (bits 17..23) is set | | ||
| 17 | lens_contamination_error | LCM error threshold triggered for at least one sector | | ||
| 18 | low_temperature_error | Current internal temperature below error threshold | | ||
| 19 | high_temperature_error | Current internal temperature above error threshold | | ||
| 20 | device_overload | Overload error – sensor CPU is in overload state | | ||
| *Defects* | | | | ||
| 30 | device_defect | Accumulative flag – set if device detected an unrecoverable defect | | ||
|
||
**R2300 4-layer:** | ||
|
||
| Topic | Type | Description | | ||
| ------------- |-------------- | -------------------------------------------------------------------------------------------------------------------------------- | | ||
| /pf/cloud | PointCloud2 | ROS standard message, see [sensor_msgs/PointCloud2](https://docs.ros.org/en/jazzy/p/sensor_msgs/interfaces/msg/PointCloud2.html) | | ||
| /r2300_header | PFR2300Header | Sensor specific message, see [pf_interfaces/msg/PFR2300Header.msg](../src/pf_interfaces/msg/PFR2300Header.msg) | | ||
|
||
Topic PFR2300Header details: | ||
|
||
| Type | Name | Description | | ||
| ------ | ----------------- | -------------------------------------------------------------------------------------- | | ||
| uint16 | magic | magic byte (0xa25c) marking the beginning of a packet | | ||
| uint16 | packet_type | scan data packet type (0x0041 - 'A' 0x0042 - 'B' 0x0043 - 'C') | | ||
| uint32 | packet_size | overall packet size in bytes (header + payload) | | ||
| uint16 | header_size | header size in bytes (offset to payload data) | | ||
| uint16 | scan_number | sequence number for scan (incremented for every scan, starting with 0, overflows) | | ||
| uint16 | packet_number | sequence number for packet (counting packets of a particular scan, starting with 1) | | ||
| | | | | ||
| uint16 | layer_index | vertical layer index (0..3) | | ||
| int32 | layer_inclination | vertical layer inclination [1/10000 degree] | | ||
| uint64 | timestamp_raw | raw timestamp of first scan point in this packet in NTP time format | | ||
| uint64 | reserved1 | reserved - all bits zero for devices without switching I/Q | | ||
| uint32 | status_flags | scan status flags | | ||
| uint32 | scan_frequency | frequency of head rotation (1/1000Hz) | | ||
| uint16 | num_points_scan | number of scan points (samples) within complete scan | | ||
| uint16 | num_points_packet | total number of scan points within this packet | | ||
| uint16 | first_index | index of first scan point within this packet | | ||
| int32 | first_angle | absolute angle of first scan point within this packet (1/10000°) | | ||
| int32 | angular_increment | delta between two succeding scan points (1/10000°) CCW rotation: +ve, CW rotation: -ve | | ||
|
||
status_flags details: | ||
|
||
| Bit | Flag name | Description | | ||
| --------------- |--------------------------- | --------------------------------------------------------------------------------- | | ||
| *Informational* | | | | ||
| 0 | scan_data_info | Accumulative flag – set if any informational flag (bits 1..7) is set | | ||
| 1 | new_settings | System settings for scan data acquisition changed during recording of this packet | | ||
| 2 | invalid_data | Consistency of scan data is not guaranteed for this packet | | ||
| 3 | unstable_rotation | Scan frequency did not match set value while recording this scan data packet | | ||
| 4 | skipped_packets | Preceding scan data packets have been skipped due to connection issues | | ||
| *Warnings* | | | | ||
| 8 | device_warning | Accumulative flag – set if any warning flag (bits 9..15) is set | | ||
| 10 | low_temperature_warning | Current internal temperature below warning threshold | | ||
| 11 | high_temperature_warning | Current internal temperature above warning threshold | | ||
| 12 | device_overload | Overload warning – sensor CPU overload is imminent | | ||
| *Errors* | | | | ||
| 16 | device_error | Accumulative flag – set if any error flag (bits 17..23) is set | | ||
| 18 | low_temperature_error | Current internal temperature below error threshold | | ||
| 19 | high_temperature_error | Current internal temperature above error threshold | | ||
| 20 | device_overload | Overload error – sensor CPU is in overload state | | ||
| *Defects* | | | | ||
| 30 | device_defect | Accumulative flag – set if device detected an unrecoverable defect | | ||
|
||
|
||
|
||
|
||
|
||
|
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Oops, something went wrong.