A python ROS package for the BlueRobotics Ping360 Sonar. The package has been tested under ROS melodic and Ubuntu 16.04. This code is mostly experimental, expect that it changes often.
Keywords: ROS, package, ping360, ping360 emulator
The source code is released under a MIT license.
Get the latest stable release here.
- Robot Operating System (ROS) (middleware for robotics),
- OpenCV
- cv_bridge
Before building from source, install ping-protocol python lib:
pip install bluerobotics-ping
To build from source, clone the latest version from this repository into your catkin workspace and compile the package using
cd catkin_workspace/src
git clone https://github.com/CentraleNantesRobotics/ping360_sonar.git
cd ../
catkin build
TODO
An example launch file has been provided example.launch:
Run the main node with:
roslaunch ping360_sonar example.launch
-
example.launch: contains the default parameteres to run the Ping360 Sonar, including the serial port and the baudrate to interface with the sonar. The rest of the parameters are documented here: Ping360 Documentation. The same parameters can also be reconfigured using the dynamic_reconfigure.
An emulated mode was added to test the package when you don't have the sonar. To run the emulated sonar, set the env variable to "true":
<env name="emulated_sonar" value="true" />
The results from the emulation should be:
Three extra parameters can be set to toggle specific topics, they are set to true by default.
<param name="enableImageTopic" value="True"/>
<param name="enableScanTopic" value="True"/>
<param name="enableDataTopic" value="True"/>
While continuously rotating the sonar, it publishes two types of messages:
- The sonar's response data (the echo intensities for a given angle & range)
- A black and white image using the date received from the sonar. Same as the one generated by the ping viewer.
-
/ping360_node/sonar/images
(sensor_msgs/Image)The generated sonar image. This topic can be toggled using the enableImageTopic parameter.
-
/ping360_node/sonar/data
(msg/SonarEcho)Publishes the raw sonar data in a custom message:
Header header #header info float32 angle # the measurement angle [rad] uint8 gain # Sonar Gain uint16 number_of_samples uint16 transmit_frequency # [kHz] uint16 speed_of_sound # [m/s] uint8 range # range value [m] uint8[] intensities # intensity data [0-255]. This is the actual data received from the sonar
This topic can be toggled using the enableDataTopic parameter.
-
/ping360_node/sonar/scan
(sensor_msgs/LaserScan)Publishes a LaserScan msg with ranges detected with a certain intensity threshold:
float32 angle_min = 0 # start angle of the scan [rad] float32 angle_max = 2*pi # end angle of the scan [rad] float32 angle_increment # angular distance between measurements, calculated using the configured Step [rad] float32 range_min = .75 # minimum range value [m] float32 range_max = sonarRange # maximum range value, it's set to the configured sonarRange [m] float32[] ranges # calculated ranges that correspond to an intensity > threshold [m] float32[] intensities # sensor intensity data [0-255]
This topic can be toggled using the enableScanTopic parameter.
Note:
- ranges values < range_min or > range_max should be discarded
- don't forget to set the frame to sonar_frame when using Rviz
Please report bugs and request features using the Issue Tracker.
Henrique Martinez Rocamora 💻 |
Anas Mazouni 💻 |
tomlogan501 🤔 |
This project follows the all-contributors specification.
Contributions of any kind welcome! Please refer to our Contribution Guide