Skip to content

Commit

Permalink
Merge pull request #21 from cyberbotics/sync
Browse files Browse the repository at this point in the history
Sync with 'webots' repo.
  • Loading branch information
DavidMansolino committed Jul 30, 2020
2 parents 546c8fa + f1d0bda commit 75adbab
Show file tree
Hide file tree
Showing 37 changed files with 3,146 additions and 45 deletions.
16 changes: 15 additions & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -76,10 +76,12 @@ find_package(catkin REQUIRED COMPONENTS roscpp rospy std_msgs sensor_msgs messag
field_set_vec2f.srv
field_set_vec3f.srv
get_bool.srv
get_float_array.srv
get_float.srv
get_int.srv
get_string.srv
get_uint64.srv
get_urdf.srv
gps_decimal_degrees_to_degrees_minutes_seconds.srv
lidar_get_frequency_info.srv
lidar_get_info.srv
Expand Down Expand Up @@ -264,8 +266,20 @@ install(TARGETS panoramic_view_recorder
install(TARGETS pioneer3at
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION})

install(PROGRAMS src/webots_launcher.py
catkin_install_python(PROGRAMS scripts/ros_controller.py
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION})

catkin_install_python(PROGRAMS scripts/ros_python.py
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION})

catkin_install_python(PROGRAMS scripts/webots_launcher.py
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION})

install(DIRECTORY launch
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})

install(DIRECTORY plugins
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})

install(DIRECTORY worlds
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
2 changes: 1 addition & 1 deletion launch/catch_the_bird.launch
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@
<include file="$(find webots_ros)/launch/webots.launch">
<arg name="mode" value="realtime"/>
<arg name="no-gui" value="$(arg no-gui)"/>
<arg name="world" value="$(env WEBOTS_HOME)/projects/languages/ros/worlds/catch_the_bird.wbt"/>
<arg name="world" value="$(find webots_ros)/worlds/catch_the_bird.wbt"/>
</include>

<arg name="auto-close" default="false" doc="Startup mode"/>
Expand Down
2 changes: 1 addition & 1 deletion launch/complete_test.launch
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@
<include file="$(find webots_ros)/launch/webots.launch">
<arg name="mode" value="realtime"/>
<arg name="no-gui" value="$(arg no-gui)"/>
<arg name="world" value="$(env WEBOTS_HOME)/projects/languages/ros/worlds/complete_test.wbt"/>
<arg name="world" value="$(find webots_ros)/worlds/complete_test.wbt"/>
</include>

<arg name="auto-close" default="false" doc="Startup mode"/>
Expand Down
2 changes: 1 addition & 1 deletion launch/e_puck_line.launch
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@
<include file="$(find webots_ros)/launch/webots.launch">
<arg name="mode" value="realtime"/>
<arg name="no-gui" value="$(arg no-gui)"/>
<arg name="world" value="$(env WEBOTS_HOME)/projects/languages/ros/worlds/e-puck_line.wbt"/>
<arg name="world" value="$(find webots_ros)/worlds/e-puck_line.wbt"/>
</include>

<arg name="duration" default="20" doc="Duration in seconds"/>
Expand Down
2 changes: 1 addition & 1 deletion launch/keyboard_teleop.launch
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@
<include file="$(find webots_ros)/launch/webots.launch">
<arg name="mode" value="realtime"/>
<arg name="no-gui" value="$(arg no-gui)"/>
<arg name="world" value="$(env WEBOTS_HOME)/projects/languages/ros/worlds/keyboard_teleop.wbt"/>
<arg name="world" value="$(find webots_ros)/worlds/keyboard_teleop.wbt"/>
</include>

<arg name="auto-close" default="false" doc="Startup mode"/>
Expand Down
2 changes: 1 addition & 1 deletion launch/panoramic_view_recorder.launch
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@
<include file="$(find webots_ros)/launch/webots.launch">
<arg name="mode" value="realtime"/>
<arg name="no-gui" value="$(arg no-gui)"/>
<arg name="world" value="$(env WEBOTS_HOME)/projects/languages/ros/worlds/panoramic_view_recorder.wbt"/>
<arg name="world" value="$(find webots_ros)/worlds/panoramic_view_recorder.wbt"/>
</include>

<arg name="auto-close" default="false" doc="Startup mode"/>
Expand Down
4 changes: 2 additions & 2 deletions launch/pioneer3at.launch
Original file line number Diff line number Diff line change
Expand Up @@ -5,9 +5,9 @@
<include file="$(find webots_ros)/launch/webots.launch">
<arg name="mode" value="realtime"/>
<arg name="no-gui" value="$(arg no-gui)"/>
<arg name="world" value="$(env WEBOTS_HOME)/projects/languages/ros/worlds/pioneer3at.wbt"/>
<arg name="world" value="$(find webots_ros)/worlds/pioneer3at.wbt"/>
</include>

<arg name="auto-close" default="false" doc="Startup mode"/>
<node name="pioneer3at" pkg="webots_ros" type="pioneer3at" required="$(arg auto-close)"/>
<node name="pioneer3at_controller" pkg="webots_ros" type="pioneer3at" required="$(arg auto-close)"/>
</launch>
2 changes: 1 addition & 1 deletion launch/robot_information_parser.launch
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@
<include file="$(find webots_ros)/launch/webots.launch">
<arg name="mode" value="realtime"/>
<arg name="no-gui" value="$(arg no-gui)"/>
<arg name="world" value="$(env WEBOTS_HOME)/projects/languages/ros/worlds/e-puck_line.wbt"/>
<arg name="world" value="$(find webots_ros)/worlds/e-puck_line.wbt"/>
</include>

<arg name="auto-close" default="false" doc="Startup mode"/>
Expand Down
17 changes: 17 additions & 0 deletions launch/webots_ros_python.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
<?xml version="1.0"?>
<launch>
<!-- start Webots -->
<arg name="no-gui" default="false," doc="Start Webots with minimal GUI"/>
<include file="$(find webots_ros)/launch/webots.launch">
<arg name="mode" value="realtime"/>
<arg name="no-gui" value="$(arg no-gui)"/>
<arg name="world" value="$(find webots_ros)/worlds/ros_python.wbt"/>
</include>

<arg name="auto-close" default="false" doc="Startup mode"/>
<env name="LD_LIBRARY_PATH" value="$(env LD_LIBRARY_PATH):$(env WEBOTS_HOME)/lib/controller"/>
<env name="PYTHONPATH" value="$(env PYTHONPATH):$(env WEBOTS_HOME)/lib/controller/python27" unless="$(eval '1' if env('ROS_DISTRO') == 'noetic' else '0')" />
<env name="PYTHONPATH" value="$(env PYTHONPATH):$(env WEBOTS_HOME)/lib/controller/python38" if="$(eval '1' if env('ROS_DISTRO') == 'noetic' else '0')" />
<node name="webots_ros_python" pkg="webots_ros" type="ros_python.py" required="$(arg auto-close)"/>
<node name="ros_controller" pkg="webots_ros" type="ros_controller.py" required="$(arg auto-close)"/>
</launch>
2 changes: 1 addition & 1 deletion package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package>
<name>webots_ros</name>
<version>2.0.6</version>
<version>2.1.0</version>
<description>The ROS package containing examples for interfacing ROS with the standard ROS controller of Webots</description>

<url>http://wiki.ros.org/webots_ros</url>
Expand Down
7 changes: 7 additions & 0 deletions plugins/robot_windows/info/info.html
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
<div>
<h2>Info window</h2>
<div>
<p>Show message received from the controller:</p>
<span id='text-display'></span>
</div>
</div>
7 changes: 7 additions & 0 deletions plugins/robot_windows/info/info.js
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
webots.window('info').receive = function(message, robot) {
if (message.startsWith('test')) {
document.querySelector("#text-display").innerHTML = message;
this.send("Answer: " + message, robot);
} else
console.log("Received unknown message for robot '" + robot + "': '" + message + "'");
}
38 changes: 38 additions & 0 deletions scripts/ros_controller.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
#!/usr/bin/env python

# Copyright 1996-2020 Cyberbotics Ltd.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

"""
This is a simple example of a Python ROS node receiving sensor values and publishing motor commands (velocity)
to drive a robot and stop it before colliding with an obstacle.
"""

import rospy
from std_msgs.msg import Float64


def callback(data):
global pub
rospy.loginfo(rospy.get_caller_id() + 'Received sensor value: %s', data.data)
if data.data > 100:
pub.publish(0)
else:
pub.publish(9)


rospy.init_node('controller', anonymous=True)
pub = rospy.Publisher('motor', Float64, queue_size=10)
rospy.Subscriber("sensor", Float64, callback)
rospy.spin()
62 changes: 62 additions & 0 deletions scripts/ros_python.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,62 @@
#!/usr/bin/env python

# Copyright 1996-2020 Cyberbotics Ltd.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

"""
This is a simple example of a Webots controller running a Python ROS node thanks to rospy.
The robot is publishing the value of its front distance sensor and receving motor commands (velocity).
"""

import rospy
from std_msgs.msg import Float64
from controller import Robot
import os


def callback(data):
global velocity
global message
message = 'Received velocity value: ' + str(data.data)
velocity = data.data


robot = Robot()
timeStep = int(robot.getBasicTimeStep())
left = robot.getMotor('motor.left')
right = robot.getMotor('motor.right')
sensor = robot.getDistanceSensor('prox.horizontal.2') # front central proximity sensor
sensor.enable(timeStep)
left.setPosition(float('inf')) # turn on velocity control for both motors
right.setPosition(float('inf'))
velocity = 0
left.setVelocity(velocity)
right.setVelocity(velocity)
message = ''
print('Initializing ROS: connecting to ' + os.environ['ROS_MASTER_URI'])
robot.step(timeStep)
rospy.init_node('listener', anonymous=True)
print('Subscribing to "motor" topic')
robot.step(timeStep)
rospy.Subscriber('motor', Float64, callback)
pub = rospy.Publisher('sensor', Float64, queue_size=10)
print('Running the control loop')
while robot.step(timeStep) != -1 and not rospy.is_shutdown():
pub.publish(sensor.getValue())
print('Published sensor value: ', sensor.getValue())
if message:
print(message)
message = ''
left.setVelocity(velocity)
right.setVelocity(velocity)
File renamed without changes.
Loading

0 comments on commit 75adbab

Please sign in to comment.