Unverified Commit 92454154 authored by Anas Mazouni's avatar Anas Mazouni Committed by GitHub
Browse files

Merge branch 'develop' into all-contributors/add-Hameck

parents ff1ff118 4c7cca4e
......@@ -12,6 +12,7 @@ find_package(catkin REQUIRED COMPONENTS
rospy
sensor_msgs
std_msgs
dynamic_reconfigure
)
find_package(OpenCV REQUIRED)
......@@ -90,10 +91,11 @@ catkin_python_setup()
## and list every .cfg file to be processed
## Generate dynamic reconfigure parameters in the 'cfg' folder
# generate_dynamic_reconfigure_options(
# cfg/DynReconf1.cfg
# cfg/DynReconf2.cfg
# )
generate_dynamic_reconfigure_options(
cfg/sonar.cfg
#...
)
###################################
## catkin specific configuration ##
......@@ -146,6 +148,7 @@ include_directories(
## Add cmake target dependencies of the executable
## same as for the library above
# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
# add_dependencies(ping360_node ${PROJECT_NAME}_gencfg)
## Specify libraries to link a library or executable target against
# target_link_libraries(${PROJECT_NAME}_node
......
# ping360_sonar
## Overview
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
### License
The source code is released under a [MIT license](LICENSE).
## Installation
### Building from Source
#### Dependencies
- [Robot Operating System (ROS)](http://wiki.ros.org) (middleware for robotics),
- opencv
- [cv_bridge]
#### Building
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_python.git
cd ../
catkin build
### Unit Tests
TODO
## Usage
An example launch file has been provided [example.launch](launch/example.launch):
Run the main node with:
roslaunch ping360_sonar example.launch
## Launch files
* **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](https://docs.bluerobotics.com/ping-protocol/pingmessage-ping360/)
## Nodes
### ping360_node
Creates a black and white OpenCv image using the date received from the sonar. Same as the one generated by the ping viewer.
#### Published Topics
* **`/ping360_sonar`** ([sensor_msgs/Image])
The generated sonar image.
## Bugs & Feature Requests
Please report bugs and request features using the [Issue Tracker](https://github.com/CentraleNantesRobotics/ping360_sonar_python/issues).
[ROS]: http://www.ros.org
[BlueRobotics]: http://bluerobotics.com
[cv_bridge]: http://wiki.ros.org/cv_bridge
[sensor_msgs/Image]: http://docs.ros.org/melodic/api/sensor_msgs/html/msg/Image.html
[Ping360]: https://bluerobotics.com/store/sensors-sonars-cameras/sonar/ping360-sonar-r1-rp/
<!-- ALL-CONTRIBUTORS-BADGE:START - Do not remove or modify this section -->
[![All Contributors](https://img.shields.io/badge/all_contributors-1-orange.svg?style=flat-square)](#contributors-)
<!-- ALL-CONTRIBUTORS-BADGE:END -->
ROS package for Blue Robotics Ping360 Sonar
## Contributors ✨
......@@ -22,3 +94,5 @@ Thanks goes to these wonderful people ([emoji key](https://allcontributors.org/d
<!-- ALL-CONTRIBUTORS-LIST:END -->
This project follows the [all-contributors](https://github.com/all-contributors/all-contributors) specification. Contributions of any kind welcome!
=======
#!/usr/bin/env python
PACKAGE = "ping360_sonar"
from dynamic_reconfigure.parameter_generator_catkin import *
gen = ParameterGenerator()
gen.add("debug", bool_t, 0, "Display Images", True)
gen.add("range", int_t, 0, "Sonar range (m)", 1, 1, 60)
gen.add("gain", int_t, 0, "Receiver Gain (Low:0 , Medium: 1, High: 2)", 0, 0, 2)
gen.add("numberOfSamples", int_t, 0, "Number of samples", 200 , 1, 2000)
gen.add("transmitFrequency", int_t, 0, "Transmit Frequency (kHz)", 740, 500 , 1000)
gen.add("speedOfSound", int_t, 0, "Speed of sound (m/s)", 1450, 1450, 1550)
gen.add("step", int_t, 0, "Filling Step", 1, 1,10)
gen.add("queueSize", int_t, 0, "Queue Size", 1, 0,10)
exit(gen.generate(PACKAGE, "ping360_sonar", "sonar"))
\ No newline at end of file
<?xml version="1.0"?>
<package format="2">
<name>ping360_sonar</name>
<version>0.0.0</version>
<version>0.1.0</version>
<description>The sonar-ping360 package</description>
<!-- One maintainer tag required, multiple allowed, one person per tag -->
<!-- Example: -->
<!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> -->
<maintainer email="stormix@todo.todo">stormix</maintainer>
<maintainer email="anas.mazouni@stormix.co">Anas Mazouni</maintainer>
<maintainer email="henrique.martinez-de-azevedo@eleves.ec-nantes.fr">Henrique Martinez de Azevedo</maintainer>
<!-- One license tag required, multiple allowed, one license per tag -->
<!-- Commonly used license strings: -->
<!-- BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 -->
<license>TODO</license>
<license>MIT</license>
<!-- Url tags are optional, but multiple are allowed, one per tag -->
<!-- Optional attribute type can be: website, bugtracker, or repository -->
<!-- Example: -->
<!-- <url type="website">http://wiki.ros.org/sonar-ping360</url> -->
<!-- Author tags are optional, multiple are allowed, one per tag -->
<!-- Authors do not have to be maintainers, but could be -->
<!-- Example: -->
<!-- <author email="jane.doe@example.com">Jane Doe</author> -->
<!-- The *depend tags are used to specify dependencies -->
<!-- Dependencies can be catkin packages or system dependencies -->
<!-- Examples: -->
<!-- Use depend as a shortcut for packages that are both build and exec dependencies -->
<!-- <depend>roscpp</depend> -->
<!-- Note that this is equivalent to the following: -->
<!-- <build_depend>roscpp</build_depend> -->
<!-- <exec_depend>roscpp</exec_depend> -->
<!-- Use build_depend for packages you need at compile time: -->
<!-- <build_depend>message_generation</build_depend> -->
<!-- Use build_export_depend for packages you need in order to build against this package: -->
<!-- <build_export_depend>message_generation</build_export_depend> -->
<!-- Use buildtool_depend for build tool packages: -->
<!-- <buildtool_depend>catkin</buildtool_depend> -->
<!-- Use exec_depend for packages you need at runtime: -->
<!-- <exec_depend>message_runtime</exec_depend> -->
<!-- Use test_depend for packages you need only for testing: -->
<!-- <test_depend>gtest</test_depend> -->
<!-- Use doc_depend for packages you need only for building documentation: -->
<!-- <doc_depend>doxygen</doc_depend> -->
<buildtool_depend>catkin</buildtool_depend>
<build_depend>cv_bridge</build_depend>
<build_depend>rospy</build_depend>
<build_depend>dynamic_reconfigure</build_depend>
<build_depend>sensor_msgs</build_depend>
<build_depend>std_msgs</build_depend>
<build_export_depend>cv_bridge</build_export_depend>
......@@ -61,11 +24,5 @@
<exec_depend>rospy</exec_depend>
<exec_depend>sensor_msgs</exec_depend>
<exec_depend>std_msgs</exec_depend>
<!-- The export tag contains other, unspecified, tags -->
<export>
<!-- Other tools can request additional information be placed here -->
</export>
<exec_depend>dynamic_reconfigure</exec_depend>
</package>
......@@ -12,37 +12,38 @@ from std_msgs.msg import String
from sensor_msgs.msg import Image
from cv_bridge import CvBridge, CvBridgeError
import rospy
from dynamic_reconfigure.server import Server
from ping360_sonar.cfg import sonarConfig
import json
def callback(config, level):
global gain, numberOfSamples, transmitFrequency, transmitDuration, sonarRange, speedOfSound, samplePeriod, debug, step, imgSize, queue_size, p
# Update Ping 360 Parameters
gain = config['gain']
numberOfSamples = config['numberOfSamples']
transmitFrequency = config['transmitFrequency']
sonarRange = config['range']
speedOfSound = config['speedOfSound']
samplePeriod = calculateSamplePeriod(sonarRange, numberOfSamples, speedOfSound)
transmitDuration = adjustTransmitDuration(sonarRange, samplePeriod, speedOfSound)
debug = config['debug']
step = config['step']
queue_size = config['queueSize']
rospy.loginfo("Reconfigure Request")
return config
def main():
try:
rospy.init_node('ping360_node')
# Ping 360 Parameters
device = rospy.get_param('~device',"/dev/ttyUSB0")
baudrate = rospy.get_param('~baudrate', 115200)
gain = rospy.get_param('~gain', 0)
numberOfSamples = rospy.get_param('~numberOfSamples', 200) # Number of points
transmitFrequency = rospy.get_param('~transmitFrequency', 740) # Default frequency
sonarRange = rospy.get_param('~sonarRange', 1) # in m
speedOfSound = rospy.get_param('~speedOfSound', 1500) # in m/s
samplePeriod = calculateSamplePeriod(sonarRange, numberOfSamples, speedOfSound)
transmitDuration = adjustTransmitDuration(sonarRange, samplePeriod, speedOfSound)
debug = rospy.get_param('~debug', True)
# Output and ROS parameters
step = rospy.get_param('~step', 1)
topic = "ping360_sonar"
imgSize = rospy.get_param('~imgSize', 500)
queue_size= rospy.get_param('~queueSize', 1)
srv = Server(sonarConfig, callback)
# Global Variables
angle = 0
p = Ping360(device, baudrate)
imagePub = rospy.Publisher(topic, Image, queue_size=queue_size)
imagePub = rospy.Publisher("ping360_sonar", Image, queue_size=queue_size)
bridge = CvBridge()
# Initialize and configure the sonar
print("Initialized: %s" % p.initialize())
p.set_gain_setting(gain)
p.set_transmit_frequency(transmitFrequency)
p.set_transmit_duration(transmitDuration)
......@@ -55,6 +56,11 @@ def main():
# Center point coordinates
center = (float(imgSize/2),float(imgSize/2))
while not rospy.is_shutdown():
p.set_gain_setting(gain)
p.set_transmit_frequency(transmitFrequency)
p.set_transmit_duration(transmitDuration)
p.set_sample_period(samplePeriod)
p.set_number_of_samples(numberOfSamples)
p.transmitAngle(angle)
data = bytearray(getattr(p,'_data'))
data_lst = [k for k in data]
......@@ -77,6 +83,8 @@ def main():
if debug:
cv2.imshow("PolarPlot",image)
cv2.waitKey(27)
else:
cv2.destroyAllWindows()
publish(image, imagePub, bridge)
rospy.sleep(0.1)
......@@ -132,3 +140,25 @@ def getSamplePeriod(samplePeriod, _samplePeriodTickDuration = 25e-9):
# type: (float, float) -> float
""" Sample period in ns """
return samplePeriod*_samplePeriodTickDuration
# Ping 360 Parameters
device = rospy.get_param('~device',"/dev/ttyUSB0")
baudrate = rospy.get_param('~baudrate', 115200)
gain = rospy.get_param('~gain', 0)
numberOfSamples = rospy.get_param('~numberOfSamples', 200) # Number of points
transmitFrequency = rospy.get_param('~transmitFrequency', 740) # Default frequency
sonarRange = rospy.get_param('~sonarRange', 1) # in m
speedOfSound = rospy.get_param('~speedOfSound', 1500) # in m/s
samplePeriod = calculateSamplePeriod(sonarRange, numberOfSamples, speedOfSound)
transmitDuration = adjustTransmitDuration(sonarRange, samplePeriod, speedOfSound)
debug = rospy.get_param('~debug', True)
# Output and ROS parameters
step = rospy.get_param('~step', 1)
imgSize = rospy.get_param('~imgSize', 500)
queue_size= rospy.get_param('~queueSize', 1)
p = Ping360(device, baudrate)
print("Initialized: %s" % p.initialize())
Supports Markdown
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment