Skip to content

Commit d0f772b

Browse files
authored
add gps_device (#208)
* add gps_device * fix check speed subscriber also and publish
1 parent b2ee7d5 commit d0f772b

File tree

2 files changed

+108
-0
lines changed

2 files changed

+108
-0
lines changed

webots_ros2_core/webots_ros2_core/devices/device_manager.py

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -24,6 +24,7 @@
2424
from .light_sensor_device import LightSensorDevice
2525
from .robot_device import RobotDevice
2626
from .imu_device import ImuDevice
27+
from .gps_device import GpsDevice
2728
from webots_ros2_core.webots.controller import Node
2829

2930

@@ -56,6 +57,8 @@ def __init__(self, node, config=None):
5657
device = DistanceSensorDevice(node, device_key, wb_device, self.__config.get(device_key, None))
5758
elif wb_device.getNodeType() == Node.LIGHT_SENSOR:
5859
device = LightSensorDevice(node, device_key, wb_device, self.__config.get(device_key, None))
60+
elif wb_device.getNodeType() == Node.GPS:
61+
device = GpsDevice(node, device_key, wb_device, self.__config.get(device_key, None))
5962

6063
# Add device to the list
6164
self.__wb_devices[device_key] = wb_device
Lines changed: 105 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,105 @@
1+
# Copyright 1996-2021 Cyberbotics Ltd.
2+
#
3+
# Licensed under the Apache License, Version 2.0 (the "License");
4+
# you may not use this file except in compliance with the License.
5+
# You may obtain a copy of the License at
6+
#
7+
# http://www.apache.org/licenses/LICENSE-2.0
8+
#
9+
# Unless required by applicable law or agreed to in writing, software
10+
# distributed under the License is distributed on an "AS IS" BASIS,
11+
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
# See the License for the specific language governing permissions and
13+
# limitations under the License.
14+
15+
"""Webots GPS device wrapper for ROS2."""
16+
17+
from rclpy.qos import qos_profile_sensor_data
18+
from std_msgs.msg import Float32
19+
from sensor_msgs.msg import NavSatFix, NavSatStatus
20+
from geometry_msgs.msg import PointStamped
21+
from .sensor_device import SensorDevice
22+
from controller import GPS
23+
24+
25+
class GpsDevice(SensorDevice):
26+
"""
27+
ROS2 wrapper for Webots GPS node.
28+
29+
Creates suitable ROS2 interface based on Webots
30+
[GPS](https://cyberbotics.com/doc/reference/gps) node instance:
31+
32+
It allows the following functinalities:
33+
- Publishes position measurements of type `sensor_msgs::NavSatFix` if WGS84
34+
- Publishes position measurements of type `geometry_msgs::PointStamped` if LOCAL
35+
36+
Args:
37+
node (WebotsNode): The ROS2 node.
38+
device_key (str): Unique identifier of the device used for configuration.
39+
wb_device (Gps): Webots node of type GPS.
40+
41+
Kwargs:
42+
params (dict): Inherited from `SensorDevice` + the following::
43+
44+
dict: {
45+
'timestep': int, # Publish period in ms (default 128ms)
46+
}
47+
48+
"""
49+
50+
def __init__(self, node, device_key, wb_device, params=None):
51+
super().__init__(node, device_key, wb_device, params)
52+
self.__speed_publisher = None
53+
self.__gps_publisher = None
54+
self.__coordinate_system = self._wb_device.getCoordinateSystem()
55+
56+
# Exit if disabled
57+
if self._disable:
58+
return
59+
60+
# Change default timestep
61+
self._timestep = 128
62+
63+
# Create topics
64+
self.__speed_publisher = node.create_publisher(
65+
Float32, self._topic_name + '/speed', qos_profile_sensor_data)
66+
67+
if self.__coordinate_system == GPS.WGS84:
68+
self.__gps_publisher = node.create_publisher(
69+
NavSatFix, self._topic_name + '/gps', qos_profile_sensor_data)
70+
else:
71+
self.__gps_publisher = node.create_publisher(
72+
PointStamped, self._topic_name + '/gps', qos_profile_sensor_data)
73+
74+
def step(self):
75+
stamp = super().step()
76+
if not stamp:
77+
return
78+
79+
if self.__gps_publisher.get_subscription_count() > 0 or \
80+
self.__speed_publisher.get_subscription_count() > 0 or \
81+
self._always_publish:
82+
self._wb_device.enable(self._timestep)
83+
msg = Float32()
84+
msg.data = self._wb_device.getSpeed()
85+
self.__speed_publisher.publish(msg)
86+
if self.__coordinate_system == GPS.WGS84:
87+
msg = NavSatFix()
88+
msg.header.stamp = stamp
89+
msg.header.frame_id = self._frame_id
90+
msg.latitude = self._wb_device.getValues()[0]
91+
msg.longitude = self._wb_device.getValues()[1]
92+
msg.altitude = self._wb_device.getValues()[2]
93+
msg.position_covariance_type = NavSatFix.COVARIANCE_TYPE_UNKNOWN
94+
msg.status.service = NavSatStatus.SERVICE_GPS
95+
self.__gps_publisher.publish(msg)
96+
else:
97+
msg = PointStamped()
98+
msg.header.stamp = stamp
99+
msg.header.frame_id = self._frame_id
100+
msg.point.x = self._wb_device.getValues()[0]
101+
msg.point.y = self._wb_device.getValues()[1]
102+
msg.point.z = self._wb_device.getValues()[2]
103+
self.__gps_publisher.publish(msg)
104+
else:
105+
self._wb_device.disable()

0 commit comments

Comments
 (0)