Skip to content

HTTPS clone URL

Subversion checkout URL

You can clone with HTTPS or Subversion.

Download ZIP
Browse files

[builder] replace configure_mw by add_stream

  • Loading branch information...
commit 680d5a5f04adcce556c29e5b0983a6c1849c4b4d 1 parent 67765ad
Pierrick Koch authored
Showing with 180 additions and 180 deletions.
  1. +2 −2 addons/io_export_morse_scene.py
  2. +3 −3 bindings/pymorse/pymorse-testing.py
  3. +2 −2 bindings/pymorse/pymorse.py
  4. +3 −3 doc/morse/user/advanced_tutorials/cat_and_mouse.rst
  5. +4 −4 doc/morse/user/advanced_tutorials/ros_tutorial.rst
  6. +2 −2 doc/morse/user/advanced_tutorials/tutorial_builder_ros.rst
  7. +1 −1  doc/morse/user/beginner_tutorials/hri_tutorial.rst
  8. +1 −1  doc/morse/user/beginner_tutorials/tutorial.rst
  9. +3 −3 doc/morse/user/beginner_tutorials/yarp_tutorial.rst
  10. +6 −6 doc/morse/user/builder.rst
  11. +11 −11 doc/morse/user/builder_example.rst
  12. +1 −1  doc/morse/user/others/human.rst
  13. +8 −8 examples/scenarii/action-1.py
  14. +3 −3 examples/scenarii/quadrotor_dynamic_example.py
  15. +3 −3 examples/scenarii/ros_depth.py
  16. +2 −2 examples/scenarii/ros_example.py
  17. +2 −2 examples/scenarii/ros_example_multi.py
  18. +5 −5 examples/scenarii/ros_example_pr2.py
  19. +9 −9 examples/scenarii/rosace-1.py
  20. +8 −8 examples/scenarii/test-1.py
  21. +3 −3 examples/tutorials/cat_mouse_game.py
  22. +4 −4 examples/tutorials/multinode/dala_simple.py
  23. +4 −4 examples/tutorials/ros_navigation/scenario.py
  24. +3 −3 examples/tutorials/tutorial-2-yarp.py
  25. +1 −1  src/morse/builder/robots/human.py
  26. +1 −1  testing/base/armature_pose_testing.py
  27. +3 −3 testing/base/armature_testing.py
  28. +1 −1  testing/base/battery_testing.py
  29. +2 −2 testing/base/destination_testing.py
  30. +1 −1  testing/base/gps_testing.py
  31. +2 −2 testing/base/gripper_testing.py
  32. +1 −1  testing/base/gyroscope_testing.py
  33. +2 −2 testing/base/light_testing.py
  34. +2 −2 testing/base/ned_testing.py
  35. +3 −3 testing/base/odometry_testing.py
  36. +3 −3 testing/base/orientation_testing.py
  37. +1 −1  testing/base/pose_testing.py
  38. +3 −3 testing/base/proximity_testing.py
  39. +3 −3 testing/base/ptu_testing.py
  40. +2 −2 testing/base/rotorcraft_waypoint_testing.py
  41. +2 −2 testing/base/semantic_camera_testing.py
  42. +1 −1  testing/base/sick_testing.py
  43. +2 −2 testing/base/stabilized_quadrirotor_testing.py
  44. +2 −2 testing/base/steer_force_testing.py
  45. +2 −2 testing/base/teleport_testing.py
  46. +2 −2 testing/base/thermometer_testing.py
  47. +2 −2 testing/base/utm_mod_testing.py
  48. +2 −2 testing/base/victim_testing.py
  49. +3 −3 testing/base/video_camera_diffimg_testing.py
  50. +2 −2 testing/base/video_camera_testing.py
  51. +2 −2 testing/base/vw_testing.py
  52. +2 −2 testing/base/waypoint_testing.py
  53. +2 −2 testing/base/xyw_testing.py
  54. +2 −2 testing/middlewares/ros/data_stream.py
  55. +3 −3 testing/middlewares/ros/depth_camera.py
  56. +3 −3 testing/middlewares/ros/sick.py
  57. +3 −3 testing/middlewares/ros/video_camera.py
  58. +2 −2 testing/middlewares/yarp/yarp_datastream_testing.py
  59. +2 −2 testing/robots/human/human_pose.py
  60. +1 −1  testing/robots/pr2/jointstate.py
  61. +3 −3 testing/robots/segway/reverse_vw.py
  62. +3 −3 testing/robots/segway/segway_vw.py
  63. +3 −3 testing/robots/segway/spiral-dala.py
  64. +3 −3 testing/robots/segway/spiral.py
  65. +2 −2 tools/io_export_morse.py
4 addons/io_export_morse_scene.py
View
@@ -170,14 +170,14 @@ def scan_config(file_out):
if isinstance (value[0], str):
mw = value[0]
mw = mw.lower()
- file_out.write("%s.configure_mw('%s', %s)\n" % (component, mw, value))
+ file_out.write("%s.add_stream('%s', %s)\n" % (component, mw, value))
# If using the new syntax that allows more than one middleware
# per component
else:
for item in value:
mw = item[0]
mw = mw.lower()
- file_out.write("%s.configure_mw('%s', %s)\n" % (component, mw, item))
+ file_out.write("%s.add_stream('%s', %s)\n" % (component, mw, item))
try:
component_config.component_service
6 bindings/pymorse/pymorse-testing.py
View
@@ -31,11 +31,11 @@ def setUpEnv(self):
robot1.translate(0.0,1.0,0.0)
battery = Sensor('battery')
- battery.configure_mw('socket')
+ battery.add_stream('socket')
robot1.append(battery)
motion = Actuator('waypoint')
- motion.configure_mw('socket')
+ motion.add_stream('socket')
motion.configure_service('socket')
robot1.append(motion)
@@ -46,7 +46,7 @@ def setUpEnv(self):
pose = Sensor('pose')
pose.name = "MyPose"
- pose.configure_mw('socket')
+ pose.add_stream('socket')
robot2.append(pose)
# Environment
4 bindings/pymorse/pymorse.py
View
@@ -48,12 +48,12 @@
pose = Sensor('pose')
pose.name = "pose"
- pose.configure_mw('socket')
+ pose.add_stream('socket')
r2d2.append(pose)
motion = Actuator('waypoint')
motion.name = "motion"
- motion.configure_mw('socket')
+ motion.add_stream('socket')
motion.configure_service('socket')
r2d2.append(motion)
6 doc/morse/user/advanced_tutorials/cat_and_mouse.rst
View
@@ -90,9 +90,9 @@ actuator to follow it.
.. code-block:: python
- V_W.configure_mw('socket')
- Semantic_L.configure_mw('socket')
- Semantic_R.configure_mw('socket')
+ V_W.add_stream('socket')
+ Semantic_L.add_stream('socket')
+ Semantic_R.add_stream('socket')
And finally we complete the scene configuration:
8 doc/morse/user/advanced_tutorials/ros_tutorial.rst
View
@@ -67,7 +67,7 @@ get some odometry feedback.
# An odometry sensor to get odometry information
odometry = Sensor('odometry')
james.append(odometry)
- odometry.configure_mw('ros')
+ odometry.add_stream('ros')
# Keyboard control
keyboard = Actuator('keyboard')
@@ -110,7 +110,7 @@ First complete the ``scenario.py`` script by adding a posture sensor:
pr2_posture = Sensor('pr2_posture')
james.append(pr2_posture)
- pr2_posture.configure_mw('ros')
+ pr2_posture.add_stream('ros')
[...]
@@ -186,7 +186,7 @@ Edit ``scenario.py`` to add a SICK sensor, configured to approximate the PR2 Hok
sick.properties(laser_range = 30.0)
sick.properties(resolution = 1.0)
sick.properties(scan_window = 180.0)
- sick.configure_mw('ros')
+ sick.add_stream('ros')
We can now build a first map of our environment. Restart the simulation with
``morse run scenario.py``.
@@ -260,7 +260,7 @@ Then, we need to add a motion controller to our robot. Open your ``scenario.py``
motion_controller = Actuator('xy_omega')
james.append(motion_controller)
- motion_controller.configure_mw('ros')
+ motion_controller.add_stream('ros')
For the navigation, we will use the high-level ``move_base`` ROS module. The
*2D Nav Goal* button in RVIZ interface will allow us to easily send navigation
4 doc/morse/user/advanced_tutorials/tutorial_builder_ros.rst
View
@@ -58,8 +58,8 @@ Configuring the middlewares
+++++++++++++++++++++++++++
.. code-block:: python
- gyroscope.configure_mw('ros')
- motion.configure_mw('ros')
+ gyroscope.add_stream('ros')
+ motion.add_stream('ros')
The middleware components will automatically be appended to the scene when necessary.
2  doc/morse/user/beginner_tutorials/hri_tutorial.rst
View
@@ -126,7 +126,7 @@ In this tutorial, we will use sockets to stream the pose out of MORSE:
# Set the pose sensor to use the socket interface to communicate
# with modules outside of MORSE.
- pose.configure_mw('socket')
+ pose.add_stream('socket')
# [...]
2  doc/morse/user/beginner_tutorials/tutorial.rst
View
@@ -103,7 +103,7 @@ with the outside world. This is done with these instructions:
.. code-block:: python
- pose.configure_mw('socket')
+ pose.add_stream('socket')
pose.configure_service('socket')
motion.configure_service('socket')
6 doc/morse/user/beginner_tutorials/yarp_tutorial.rst
View
@@ -53,9 +53,9 @@ This is done with these lines:
.. code-block:: python
- Motion_Controller.configure_mw('yarp')
- Pose.configure_mw('yarp')
- Camera.configure_mw('yarp')
+ Motion_Controller.add_stream('yarp')
+ Pose.add_stream('yarp')
+ Camera.add_stream('yarp')
This will fill up the necessary information into the ``component_config.py`` file
inside the newly created Blender scenario.
12 doc/morse/user/builder.rst
View
@@ -65,7 +65,7 @@ The Component classes
The class ``Component`` inherits directly from ``AbstractComponent`` and adds
more functions:
- * **configure_mw**: Do the binding between a component and the method to
+ * **add_stream**: Do the binding between a component and the method to
export/import its data. This must be used in general by sensors and
actuators. A single component can make several calls to this function to add
bindings with more than one middleware. The parameter can be either the name
@@ -336,18 +336,18 @@ added to the scene when the builder script is parsed.
In order to set a component-middleware-method, we have two options, the first
one is simple for the user, but requires some pre-configuration (a dictionary
-defined in the file ``src/morse/builder/data.py``). The argument of the 'configure_mw'
+defined in the file ``src/morse/builder/data.py``). The argument of the 'add_stream'
method is a string with the name of the middleware.
.. code-block:: python
- motion.configure_mw('ros')
- motion.configure_mw('yarp')
+ motion.add_stream('ros')
+ motion.add_stream('yarp')
cf. ``morse.builder.data.MORSE_DATASTREAM_DICT``
More than one middleware can be configured for the same component, by using
-several calls to the component.configure_mw method.
+several calls to the component.add_stream method.
The second one is a bit less simple for the end-user.
It consists of including the description of the middleware binding just as it
@@ -355,7 +355,7 @@ would be done by hand in the ``component_config.py`` script:
.. code-block:: python
- motion.configure_mw('ros', 'read_twist', 'morse/middleware/ros/read_vw_twist')
+ motion.add_stream('ros', 'read_twist', 'morse/middleware/ros/read_vw_twist')
cf. :doc:`hooks <../user/hooks>` and the tutorial on :doc:`manually building a scene
<../user/advanced_tutorials/editing_in_blender>` (in particular the section configuring middleware) for details.
22 doc/morse/user/builder_example.rst
View
@@ -43,12 +43,12 @@ Let's have a look to a typical ``Builder`` script, and explain it, step by step:
cam.properties(cam_width = 128, cam_height = 128)
# Configure the middlewares
- motion.configure_mw('ros')
- odometry.configure_mw('ros')
- proximity.configure_mw('ros')
- pose.configure_mw('ros')
- sick.configure_mw('ros')
- cam.configure_mw('ros')
+ motion.add_stream('ros')
+ odometry.add_stream('ros')
+ proximity.add_stream('ros')
+ pose.add_stream('ros')
+ sick.add_stream('ros')
+ cam.add_stream('ros')
env = Environment('land-1/trees')
env.place_camera([-5.0, 5.0, 3.0])
@@ -146,21 +146,21 @@ Middleware configuration
For usual sensors and actuators, configuring a middleware to access the
component is as easy as::
- motion.configure_mw('ros')
+ motion.add_stream('ros')
One component can be made accessible through several middleware by simply
-calling again ``configure_mw``::
+calling again ``add_stream``::
- motion.configure_mw('yarp')
+ motion.add_stream('yarp')
You can check which sensors and actuators are supported by which middleware in
the :doc:`compatibility matrix <integration>`.
.. note::
Sometimes, you will need to use a specific serialization method.
- This can be achieved by passing more parameters to ``configure_mw``::
+ This can be achieved by passing more parameters to ``add_stream``::
- motion.configure_mw('ros', 'read_twist', 'morse/middleware/ros/read_vw_twist')
+ motion.add_stream('ros', 'read_twist', 'morse/middleware/ros/read_vw_twist')
In that case, we instruct MORSE to use ROS with the ``read_twist`` method
defined in the ``morse.middleware.ros.read_vw_twist`` module.
2  doc/morse/user/others/human.rst
View
@@ -72,7 +72,7 @@ Usage example:
human.translate(x=5.5, y=-3.2, z=0.0)
human.rotate(z=-3.0)
- human.armature.configure_mw('pocolibs',
+ human.armature.add_stream('pocolibs',
['morse.middleware.pocolibs_datastream.Pocolibs',
'export_posture',
'morse/middleware/pocolibs/sensors/human_posture',
16 examples/scenarii/action-1.py
View
@@ -66,16 +66,16 @@
# Scene configuration
-GPS_001.configure_mw('yarp')
-CameraMain_002.configure_mw('yarp')
-Motion_Controller.configure_mw('yarp')
-Gyroscope_001.configure_mw('yarp')
+GPS_001.add_stream('yarp')
+CameraMain_002.add_stream('yarp')
+Motion_Controller.add_stream('yarp')
+Gyroscope_001.add_stream('yarp')
-Platine.configure_mw('yarp')
+Platine.add_stream('yarp')
-Motion_Controller_001.configure_mw('pocolibs')
-Stereo.configure_mw('pocolibs')
-Gyroscope.configure_mw('pocolibs')
+Motion_Controller_001.add_stream('pocolibs')
+Stereo.add_stream('pocolibs')
+Gyroscope.add_stream('pocolibs')
GPS_001.configure_modifier('NED')
Motion_Controller.configure_modifier('NED')
6 examples/scenarii/quadrotor_dynamic_example.py
View
@@ -16,12 +16,12 @@
if waypoint_controller:
motion = Actuator('rotorcraft_waypoint')
motion.name = 'waypoint'
- motion.configure_mw('ros')
+ motion.add_stream('ros')
else:
# simple controller taking RC-like roll/pitch/yaw/thrust input
motion = Actuator('rotorcraft_attitude')
motion.name = 'attitude'
- motion.configure_mw('ros', 'read_ctrl_input', 'morse/middleware/ros/read_asctec_ctrl_input')
+ motion.add_stream('ros', 'read_ctrl_input', 'morse/middleware/ros/read_asctec_ctrl_input')
Quadrotor.append(motion)
@@ -29,7 +29,7 @@
imu.name = 'imu'
# IMU with z-axis down (NED)
imu.rotate(x=math.pi)
-imu.configure_mw('ros')
+imu.add_stream('ros')
Quadrotor.append(imu)
env = Environment('indoors-1/indoor-1')
6 examples/scenarii/ros_depth.py
View
@@ -8,14 +8,14 @@
motion.translate(z=0.3)
motion.name = 'Motion'
atrv.append(motion)
-motion.configure_mw('ros')
+motion.add_stream('ros')
# Append an Odometry sensor
odometry = Sensor('odometry')
odometry.name = 'Odometry'
odometry.translate(z=0.73)
atrv.append(odometry)
-odometry.configure_mw('ros')
+odometry.add_stream('ros')
# Append a camera
camera = Sensor('depth_camera')
@@ -26,7 +26,7 @@
capturing = True, Depth = True)
camera.frequency(15)
atrv.append(camera)
-camera.configure_mw('ros')
+camera.add_stream('ros')
env = Environment('indoors-1/indoor-1')
env.aim_camera([1.0470, 0, 0.7854])
4 examples/scenarii/ros_example.py
View
@@ -16,8 +16,8 @@
atrv.append(gyroscope)
# Configuring the middlewares
-gyroscope.configure_mw('ros')
-motion.configure_mw('ros')
+gyroscope.add_stream('ros')
+motion.add_stream('ros')
env = Environment('indoors-1/indoor-1')
env.aim_camera([1.0470, 0, 0.7854])
4 examples/scenarii/ros_example_multi.py
View
@@ -17,8 +17,8 @@ def import_atrv(mw):
atrv.append(gyroscope)
# Configuring the middlewares
- gyroscope.configure_mw(mw)
- motion.configure_mw(mw)
+ gyroscope.add_stream(mw)
+ motion.add_stream(mw)
return atrv
atrv1 = import_atrv('ros')
10 examples/scenarii/ros_example_pr2.py
View
@@ -47,11 +47,11 @@
james.append(keyboard)
# Configuring the middlewares
-Pose_sensor.configure_mw('ros')
-Sick.configure_mw('ros')
-Motion_Controller.configure_mw('ros')
-IMU.configure_mw('ros')
-pr2_posture.configure_mw('ros', 'post_jointState', 'morse/middleware/ros/pr2_posture')
+Pose_sensor.add_stream('ros')
+Sick.add_stream('ros')
+Motion_Controller.add_stream('ros')
+IMU.add_stream('ros')
+pr2_posture.add_stream('ros', 'post_jointState', 'morse/middleware/ros/pr2_posture')
# Add passive objects
cornflakes = PassiveObject('props/kitchen_objects', 'Cornflakes')
18 examples/scenarii/rosace-1.py
View
@@ -60,15 +60,15 @@
ATRV_001.append(Thermometer_001)
-GPS.configure_mw('yarp', 'post_json_message', 'morse/middleware/yarp/json_mod')
-Motion_Controller.configure_mw('yarp', 'read_json_waypoint', 'morse/middleware/yarp/json_mod')
-Rosace_Sensor.configure_mw('yarp', 'post_json_message', 'morse/middleware/yarp/json_mod')
-Proximity_Sensor.configure_mw('yarp', 'post_json_message', 'morse/middleware/yarp/json_mod')
-
-Rosace_Sensor_001.configure_mw('yarp', 'post_json_message', 'morse/middleware/yarp/json_mod')
-GPS_001.configure_mw('yarp', 'post_json_message', 'morse/middleware/yarp/json_mod')
-Proximity_Sensor_001.configure_mw('yarp', 'post_json_message', 'morse/middleware/yarp/json_mod')
-Motion_Controller_001.configure_mw('yarp', 'read_json_waypoint', 'morse/middleware/yarp/json_mod')
+GPS.add_stream('yarp', 'post_json_message', 'morse/middleware/yarp/json_mod')
+Motion_Controller.add_stream('yarp', 'read_json_waypoint', 'morse/middleware/yarp/json_mod')
+Rosace_Sensor.add_stream('yarp', 'post_json_message', 'morse/middleware/yarp/json_mod')
+Proximity_Sensor.add_stream('yarp', 'post_json_message', 'morse/middleware/yarp/json_mod')
+
+Rosace_Sensor_001.add_stream('yarp', 'post_json_message', 'morse/middleware/yarp/json_mod')
+GPS_001.add_stream('yarp', 'post_json_message', 'morse/middleware/yarp/json_mod')
+Proximity_Sensor_001.add_stream('yarp', 'post_json_message', 'morse/middleware/yarp/json_mod')
+Motion_Controller_001.add_stream('yarp', 'read_json_waypoint', 'morse/middleware/yarp/json_mod')
Motion_Controller.configure_service('yarp_json')
Rosace_Sensor_001.configure_service('yarp_json')
16 examples/scenarii/test-1.py
View
@@ -37,16 +37,16 @@
cam.properties(cam_width = 128, cam_height = 128)
# Configure the middlewares
-motion.configure_mw('yarp')
-odometry.configure_mw('yarp')
-proximity.configure_mw('yarp')
-pose.configure_mw('yarp')
-sick.configure_mw('yarp')
-cam.configure_mw('yarp')
+motion.add_stream('yarp')
+odometry.add_stream('yarp')
+proximity.add_stream('yarp')
+pose.add_stream('yarp')
+sick.add_stream('yarp')
+cam.add_stream('yarp')
# Configure the middlewares
-motion.configure_mw('socket')
-pose.configure_mw('socket')
+motion.add_stream('socket')
+pose.add_stream('socket')
env = Environment('laas/grande_salle')
env.aim_camera([1.0470, 0, 0.7854])
6 examples/tutorials/cat_mouse_game.py
View
@@ -18,9 +18,9 @@
Semantic_R.name = "Camera_R"
Cat.append(Semantic_R)
-V_W.configure_mw('socket')
-Semantic_L.configure_mw('socket')
-Semantic_R.configure_mw('socket')
+V_W.add_stream('socket')
+Semantic_L.add_stream('socket')
+Semantic_R.add_stream('socket')
Mouse = Robot('atrv')
8 examples/tutorials/multinode/dala_simple.py
View
@@ -27,9 +27,9 @@ def equipped_robot(mw='yarp'):
cam.properties(cam_width = 128, cam_height = 128)
# Configure the middlewares
- motion.configure_mw(mw)
- pose.configure_mw(mw)
- sick.configure_mw(mw)
- cam.configure_mw(mw)
+ motion.add_stream(mw)
+ pose.add_stream(mw)
+ sick.add_stream(mw)
+ cam.add_stream(mw)
return (atrv)
8 examples/tutorials/ros_navigation/scenario.py
View
@@ -8,15 +8,15 @@
# Sensors and Actuators for navigation stack
pr2_posture = Sensor('pr2_posture')
james.append(pr2_posture)
-pr2_posture.configure_mw('ros')
+pr2_posture.add_stream('ros')
motion_controller = Actuator('xy_omega')
james.append(motion_controller)
-motion_controller.configure_mw('ros')
+motion_controller.add_stream('ros')
odometry = Sensor('odometry')
james.append(odometry)
-odometry.configure_mw('ros')
+odometry.add_stream('ros')
Sick = Sensor('sick')
Sick.translate(x=0.275, z=0.252)
@@ -25,7 +25,7 @@
Sick.properties(laser_range=30.0000)
Sick.properties(resolution=1.0000)
Sick.properties(scan_window=180.0000)
-Sick.configure_mw('ros')
+Sick.add_stream('ros')
# Keyboard control
keyboard = Actuator('keyboard')
6 examples/tutorials/tutorial-2-yarp.py
View
@@ -16,9 +16,9 @@
# Scene configuration
-Motion_Controller.configure_mw('yarp')
-Pose.configure_mw('yarp')
-Camera.configure_mw('yarp')
+Motion_Controller.add_stream('yarp')
+Pose.add_stream('yarp')
+Camera.add_stream('yarp')
env = Environment('indoors-1/indoor-1')
env.aim_camera([1.0470, 0, 0.7854])
2  src/morse/builder/robots/human.py
View
@@ -23,7 +23,7 @@ class Human(Robot):
human.translate(x=5.5, y=-3.2, z=0.0)
human.rotate(z=-3.0)
- human.armature.configure_mw('pocolibs',
+ human.armature.add_stream('pocolibs',
['Pocolibs',
'export_posture',
'morse/middleware/pocolibs/sensors/human_posture',
2  testing/base/armature_pose_testing.py
View
@@ -30,7 +30,7 @@ def setUpEnv(self):
kuka_posture = ArmaturePose('arm_pose')
kuka_lwr.append(kuka_posture)
- kuka_posture.configure_mw('socket')
+ kuka_posture.add_stream('socket')
kuka_posture.configure_service('socket')
env = Environment('empty', fastmode = True)
6 testing/base/armature_testing.py
View
@@ -27,17 +27,17 @@ def setUpEnv(self):
arm = KukaLWR()
robot.append(arm)
arm.translate(z=0.9)
- arm.configure_mw('socket')
+ arm.add_stream('socket')
arm.configure_service('socket')
pose = Pose()
- pose.configure_mw('socket')
+ pose.add_stream('socket')
pose.translate(z=1.3)
arm.append(pose)
arm_pose = ArmaturePose()
arm.append(arm_pose)
- arm_pose.configure_mw('socket')
+ arm_pose.add_stream('socket')
motion = Teleport()
robot.append(motion)
2  testing/base/battery_testing.py
View
@@ -24,7 +24,7 @@ def setUpEnv(self):
robot = ATRV()
battery = Battery()
- battery.configure_mw('socket')
+ battery.add_stream('socket')
battery.properties(DischargingRate = 10.0)
robot.append(battery)
4 testing/base/destination_testing.py
View
@@ -29,12 +29,12 @@ def setUpEnv(self):
robot.translate(0.0, 0.0, 20.0)
pose = Pose()
- pose.configure_mw('socket')
+ pose.add_stream('socket')
robot.append(pose)
destination = Destination('destination')
robot.append(destination)
- destination.configure_mw('socket')
+ destination.add_stream('socket')
destination.properties(Speed=2.0, Tolerance=0.3)
env = Environment('empty', fastmode = True)
2  testing/base/gps_testing.py
View
@@ -24,7 +24,7 @@ def setUpEnv(self):
robot.translate(10.0, 8.0, 0.0)
gps = GPS()
- gps.configure_mw('socket')
+ gps.add_stream('socket')
robot.append(gps)
env = Environment('empty', fastmode = True)
4 testing/base/gripper_testing.py
View
@@ -30,7 +30,7 @@ def setUpEnv(self):
arm = KukaLWR()
robot.append(arm)
arm.translate(x=0.5, z=0.9)
- arm.configure_mw('socket')
+ arm.add_stream('socket')
arm.configure_service('socket')
gripper = Gripper('gripper')
@@ -40,7 +40,7 @@ def setUpEnv(self):
teleport = Teleport()
robot.append(teleport)
- teleport.configure_mw('socket')
+ teleport.add_stream('socket')
tape1 = PassiveObject(prefix='BlackVideotape')
tape1.properties(Object = True, Graspable = True, Label = "BlackTape")
2  testing/base/gyroscope_testing.py
View
@@ -25,7 +25,7 @@ def setUpEnv(self):
robot.rotate(math.pi/16, math.pi/8, math.pi/2)
gyro = Gyroscope()
- gyro.configure_mw('socket')
+ gyro.add_stream('socket')
robot.append(gyro)
env = Environment('empty', fastmode = True)
4 testing/base/light_testing.py
View
@@ -27,13 +27,13 @@ def setUpEnv(self):
cam_focal = 25.0000, Vertical_Flip = True)
cam.translate(x=0.2, z=0.9)
atrv.append(cam)
- cam.configure_mw('socket')
+ cam.add_stream('socket')
light = Light('light')
light.translate(x=0.2, z=1.1)
light.properties(Distance = 50.0)
atrv.append(light)
- light.configure_mw('socket')
+ light.add_stream('socket')
block = PassiveObject('environments/indoors-1/boxes', 'GreenBox')
block.translate(x=2, y=0, z=1)
4 testing/base/ned_testing.py
View
@@ -26,12 +26,12 @@ def setUpEnv(self):
pose = Pose()
robot.append(pose)
- pose.configure_mw('socket')
+ pose.add_stream('socket')
pose2 = Pose()
pose2.configure_modifier('NED')
robot.append(pose2)
- pose2.configure_mw('socket')
+ pose2.add_stream('socket')
env = Environment('empty', fastmode = True)
6 testing/base/odometry_testing.py
View
@@ -27,15 +27,15 @@ def setUpEnv(self):
pose = Pose()
robot.append(pose)
- pose.configure_mw('socket')
+ pose.add_stream('socket')
motion = MotionVW('motion')
robot.append(motion)
- motion.configure_mw('socket')
+ motion.add_stream('socket')
odo = Odometry()
robot.append(odo)
- odo.configure_mw('socket')
+ odo.add_stream('socket')
env = Environment('empty', fastmode = True)
env.configure_service('socket')
6 testing/base/orientation_testing.py
View
@@ -28,15 +28,15 @@ def setUpEnv(self):
robot.translate(10.0, 8.0, 20.0)
gyro = Gyroscope()
- gyro.configure_mw('socket')
+ gyro.add_stream('socket')
robot.append(gyro)
orientation = Orientation('orientation')
- orientation.configure_mw('socket')
+ orientation.add_stream('socket')
robot.append(orientation)
pose = Pose()
- pose.configure_mw('socket')
+ pose.add_stream('socket')
robot.append(pose)
env = Environment('empty', fastmode = True)
2  testing/base/pose_testing.py
View
@@ -24,7 +24,7 @@ def setUpEnv(self):
robot = ATRV()
pose = Pose()
- pose.configure_mw('socket')
+ pose.add_stream('socket')
pose.translate(z=-0.10) # atrv sensor is at 10cm on the groud
robot.append(pose)
6 testing/base/proximity_testing.py
View
@@ -30,16 +30,16 @@ def setUpEnv(self):
proximity.properties(Track = "Catch_me")
proximity.properties(Range = 2.0)
robot.append(proximity)
- proximity.configure_mw('socket')
+ proximity.add_stream('socket')
proximity.configure_service('socket')
pose = Pose()
robot.append(pose)
- pose.configure_mw('socket')
+ pose.add_stream('socket')
motion = Teleport()
robot.append(motion)
- motion.configure_mw('socket')
+ motion.add_stream('socket')
target1 = ATRV("Target1")
target1.properties(Catch_me = True)
6 testing/base/ptu_testing.py
View
@@ -30,18 +30,18 @@ def setUpEnv(self):
robot = ATRV()
ptu = PTU()
- ptu.configure_mw('socket')
+ ptu.add_stream('socket')
ptu.translate(x=ptu_x, z=ptu_z)
ptu.configure_service('socket')
ptu.properties(Speed = 0.5)
robot.append(ptu)
posture = PTUPosture()
- posture.configure_mw('socket')
+ posture.add_stream('socket')
ptu.append(posture)
gyro = Gyroscope()
- gyro.configure_mw('socket')
+ gyro.add_stream('socket')
ptu.append(gyro)
chair = PassiveObject(prefix='RollingChair')
4 testing/base/rotorcraft_waypoint_testing.py
View
@@ -24,11 +24,11 @@ def setUpEnv(self):
pose = Pose()
robot.append(pose)
- pose.configure_mw('socket')
+ pose.add_stream('socket')
motion = RotorcraftWaypoint('motion')
robot.append(motion)
- motion.configure_mw('socket')
+ motion.add_stream('socket')
motion.configure_service('socket')
env = Environment('empty', fastmode = True)
4 testing/base/semantic_camera_testing.py
View
@@ -29,11 +29,11 @@ def setUpEnv(self):
camera = SemanticCamera()
robot.append(camera)
camera.translate(x=0.3, z=0.762)
- camera.configure_mw('socket')
+ camera.add_stream('socket')
motion = Teleport()
robot.append(motion)
- motion.configure_mw('socket')
+ motion.add_stream('socket')
env = Environment('indoors-1/boxes')
env.configure_service('socket')
2  testing/base/sick_testing.py
View
@@ -29,7 +29,7 @@ def setUpEnv(self):
sick.properties(laser_range = 10.0, Visible_arc = False)
sick.create_laser_arc()
robot.append(sick)
- sick.configure_mw('socket')
+ sick.add_stream('socket')
env = Environment('indoors-1/boxes', fastmode = True)
env.configure_service('socket')
4 testing/base/stabilized_quadrirotor_testing.py
View
@@ -27,12 +27,12 @@ def setUpEnv(self):
robot = QUAD2012('robot')
pose = Pose()
- pose.configure_mw('socket')
+ pose.add_stream('socket')
robot.append(pose)
motion = StabilizedQuadrotor('motion')
robot.append(motion)
- motion.configure_mw('socket')
+ motion.add_stream('socket')
env = Environment('empty', fastmode = True)
env.configure_service('socket')
4 testing/base/steer_force_testing.py
View
@@ -28,12 +28,12 @@ def setUpEnv(self):
robot = Hummer('robot')
pose = Pose()
- pose.configure_mw('socket')
+ pose.add_stream('socket')
robot.append(pose)
steer_force = SteerForce()
robot.append(steer_force)
- steer_force.configure_mw('socket')
+ steer_force.add_stream('socket')
env = Environment('land-1/rosace_1', fastmode = True)
env.configure_service('socket')
4 testing/base/teleport_testing.py
View
@@ -31,11 +31,11 @@ def setUpEnv(self):
robot.translate(10.0, 8.0, 20.0)
pose = Pose()
- pose.configure_mw('socket')
+ pose.add_stream('socket')
robot.append(pose)
teleport = Teleport('teleport')
- teleport.configure_mw('socket')
+ teleport.add_stream('socket')
robot.append(teleport)
4 testing/base/thermometer_testing.py
View
@@ -24,11 +24,11 @@ def setUpEnv(self):
thermometer = Thermometer()
robot.append(thermometer)
- thermometer.configure_mw('socket')
+ thermometer.add_stream('socket')
motion = Teleport()
robot.append(motion)
- motion.configure_mw('socket')
+ motion.add_stream('socket')
env = Environment('land-1/rosace_1', fastmode = True)
env.properties(Temperature='25.0')
4 testing/base/utm_mod_testing.py
View
@@ -24,11 +24,11 @@ def setUpEnv(self):
robot.translate(10.0, 8.0, 0.0)
gps = GPS()
- gps.configure_mw('socket')
+ gps.add_stream('socket')
robot.append(gps)
gps_mod = GPS()
- gps_mod.configure_mw('socket')
+ gps_mod.add_stream('socket')
gps_mod.configure_modifier('UTM')
robot.append(gps_mod)
4 testing/base/victim_testing.py
View
@@ -26,7 +26,7 @@ def setUpEnv(self):
victim_detector = Rosace()
robot.append(victim_detector)
- victim_detector.configure_mw('socket')
+ victim_detector.add_stream('socket')
victim_detector.configure_service('socket')
victim_detector.properties( Heal_range=1.0, Abilities="1,2,3,4,5")
@@ -35,7 +35,7 @@ def setUpEnv(self):
motion = Teleport()
robot.append(motion)
- motion.configure_mw('socket')
+ motion.add_stream('socket')
env = Environment('empty', fastmode = True)
env.properties(Temperature='25.0')
6 testing/base/video_camera_diffimg_testing.py
View
@@ -149,14 +149,14 @@ def setUpEnv(self):
camera.properties(Vertical_Flip = True)
camera.translate(x=0.2, z=0.9)
atrv.append(camera)
- camera.configure_mw('socket')
+ camera.add_stream('socket')
orientation = Orientation('orientation')
- orientation.configure_mw('socket')
+ orientation.add_stream('socket')
atrv.append(orientation)
gyroscope = Gyroscope('gyroscope')
- gyroscope.configure_mw('socket')
+ gyroscope.add_stream('socket')
atrv.append(gyroscope)
env = Environment('indoors-1/boxes')
4 testing/base/video_camera_testing.py
View
@@ -36,10 +36,10 @@ def setUpEnv(self):
cam.properties(Vertical_Flip = True)
cam.translate(x=0.2, z=0.9)
atrv.append(cam)
- cam.configure_mw('socket')
+ cam.add_stream('socket')
orientation = Orientation('orientation')
- orientation.configure_mw('socket')
+ orientation.add_stream('socket')
atrv.append(orientation)
env = Environment('indoors-1/boxes')
4 testing/base/vw_testing.py
View
@@ -36,11 +36,11 @@ def setUpEnv(self):
pose = Pose()
pose.translate(z=-0.10) # atrv base is 10cm over ground
robot.append(pose)
- pose.configure_mw('socket')
+ pose.add_stream('socket')
motion = MotionVW()
robot.append(motion)
- motion.configure_mw('socket')
+ motion.add_stream('socket')
motion.configure_service('socket')
env = Environment('empty', fastmode = True)
4 testing/base/waypoint_testing.py
View
@@ -28,11 +28,11 @@ def setUpEnv(self):
pose = Pose('pose')
pose.translate(z=-0.10) # atrv body
robot.append(pose)
- pose.configure_mw('socket')
+ pose.add_stream('socket')
motion = Waypoint('motion')
robot.append(motion)
- motion.configure_mw('socket')
+ motion.add_stream('socket')
motion.configure_service('socket')
4 testing/base/xyw_testing.py
View
@@ -31,11 +31,11 @@ def setUpEnv(self):
pose = Pose()
pose.translate(z=-0.10) # atrv base is 10cm over ground
robot.append(pose)
- pose.configure_mw('socket')
+ pose.add_stream('socket')
motion = MotionXYW('motion')
robot.append(motion)
- motion.configure_mw('socket')
+ motion.add_stream('socket')
motion.configure_service('socket')
env = Environment('empty', fastmode = True)
4 testing/middlewares/ros/data_stream.py
View
@@ -43,11 +43,11 @@ def setUpEnv(self):
pose = Pose()
robot.append(pose)
- pose.configure_mw('ros')
+ pose.add_stream('ros')
motion = MotionVW()
robot.append(motion)
- motion.configure_mw('ros')
+ motion.add_stream('ros')
env = Environment('empty', fastmode = True)
env.configure_service('socket')
6 testing/middlewares/ros/depth_camera.py
View
@@ -36,12 +36,12 @@ def setUpEnv(self):
motion = MotionVW('MotionVW')
robot.append(motion)
- motion.configure_mw('ros')
+ motion.add_stream('ros')
odometry = Odometry('Odometry')
odometry.translate(z=0.73)
robot.append(odometry)
- odometry.configure_mw('ros')
+ odometry.add_stream('ros')
camera = DepthCamera('DepthCamera')
camera.properties(cam_near=1.0, cam_far=20.0, Depth=True,\
@@ -49,7 +49,7 @@ def setUpEnv(self):
camera.translate(x=0.3, z=0.76)
camera.frequency(3)
robot.append(camera)
- camera.configure_mw('ros')
+ camera.add_stream('ros')
env = Environment('indoors-1/boxes')
# No fastmode here, no MaterialIndex in WIREFRAME mode: AttributeError:
6 testing/middlewares/ros/sick.py
View
@@ -36,19 +36,19 @@ def setUpEnv(self):
motion = MotionVW('MotionVW')
robot.append(motion)
- motion.configure_mw('ros')
+ motion.add_stream('ros')
odometry = Odometry('Odometry')
odometry.translate(z=0.73)
robot.append(odometry)
- odometry.configure_mw('ros')
+ odometry.add_stream('ros')
sick = Sick('Sick')
sick.translate(x = 0.18, z = 0.94)
robot.append(sick)
# sick.properties(scan_window = 270, resolution = .25)
sick.properties(scan_window = 180, resolution = 1)
- sick.configure_mw('ros')
+ sick.add_stream('ros')
# test does not call sick.__del__() so create laser arc manually
sick.create_laser_arc()
6 testing/middlewares/ros/video_camera.py
View
@@ -36,19 +36,19 @@ def setUpEnv(self):
motion = MotionVW('MotionVW')
robot.append(motion)
- motion.configure_mw('ros')
+ motion.add_stream('ros')
odometry = Odometry('Odometry')
odometry.translate(z=0.73)
robot.append(odometry)
- odometry.configure_mw('ros')
+ odometry.add_stream('ros')
camera = VideoCamera('Camera')
camera.properties(cam_width=128, cam_height=128, capturing=True, Vertical_Flip=True)
camera.translate(x=0.3, z=0.76)
camera.frequency(3)
robot.append(camera)
- camera.configure_mw('ros')
+ camera.add_stream('ros')
env = Environment('indoors-1/boxes')
# No fastmode here, no MaterialIndex in WIREFRAME mode: AttributeError:
4 testing/middlewares/yarp/yarp_datastream_testing.py
View
@@ -52,11 +52,11 @@ def setUpEnv(self):
pose = Sensor('pose')
pose.translate(z=-0.10)
robot.append(pose)
- pose.configure_mw('yarp')
+ pose.add_stream('yarp')
motion = Actuator('v_omega')
robot.append(motion)
- motion.configure_mw('yarp')
+ motion.add_stream('yarp')
env = Environment('empty', fastmode = True)
env.configure_service('socket')
4 testing/robots/human/human_pose.py
View
@@ -24,11 +24,11 @@ def setUpEnv(self):
pose = Pose()
human.append(pose)
- pose.configure_mw('socket')
+ pose.add_stream('socket')
motion = Waypoint()
human.append(motion)
- motion.configure_mw('socket')
+ motion.add_stream('socket')
motion.configure_service('socket')
env = Environment('empty', fastmode = True)
2  testing/robots/pr2/jointstate.py
View
@@ -30,7 +30,7 @@ def setUpEnv(self):
pr2 = PR2()
pr2_posture = PR2Posture()
pr2.append(pr2_posture)
- pr2_posture.configure_mw('ros')
+ pr2_posture.add_stream('ros')
env = Environment('indoors-1/indoor-1')
env.aim_camera([1.0470, 0, 0.7854])
6 testing/robots/segway/reverse_vw.py
View
@@ -41,12 +41,12 @@ def setUpEnv(self):
pose = Pose('Pose')
robot.append(pose)
- pose.configure_mw('socket')
- pose.configure_mw('text')
+ pose.add_stream('socket')
+ pose.add_stream('text')
motion = MotionVWDiff('MotionVWDiff')
robot.append(motion)
- motion.configure_mw('socket')
+ motion.add_stream('socket')
motion.configure_service('socket')
env = Environment('empty', fastmode = True)
6 testing/robots/segway/segway_vw.py
View
@@ -57,12 +57,12 @@ def setUpEnv(self):
pose = Pose()
robot.append(pose)
pose.translate(z=-0.1)
- pose.configure_mw('socket')
- pose.configure_mw('text')
+ pose.add_stream('socket')
+ pose.add_stream('text')
motion = MotionVWDiff()
robot.append(motion)
- motion.configure_mw('socket')
+ motion.add_stream('socket')
motion.configure_service('socket')
env = Environment('empty', fastmode = True)
6 testing/robots/segway/spiral-dala.py
View
@@ -40,12 +40,12 @@ def setUpEnv(self):
pose = Pose('Pose')
robot.append(pose)
- pose.configure_mw('socket')
- pose.configure_mw('text')
+ pose.add_stream('socket')
+ pose.add_stream('text')
motion = MotionVW('MotionVW')
robot.append(motion)
- motion.configure_mw('socket')
+ motion.add_stream('socket')
motion.configure_service('socket')
env = Environment('empty', fastmode = True)
6 testing/robots/segway/spiral.py
View
@@ -58,12 +58,12 @@ def setUpEnv(self):
pose = Pose('Pose')
robot.append(pose)
- pose.configure_mw('socket')
- pose.configure_mw('text')
+ pose.add_stream('socket')
+ pose.add_stream('text')
motion = MotionVWDiff('MotionVWDiff')
robot.append(motion)
- motion.configure_mw('socket')
+ motion.add_stream('socket')
motion.configure_service('socket')
env = Environment('empty', fastmode = True)
4 tools/io_export_morse.py
View
@@ -170,14 +170,14 @@ def scan_config(file_out):
if isinstance (value[0], str):
mw = value[0]
mw = mw.lower()
- file_out.write("%s.configure_mw('%s', %s)\n" % (component, mw, value))
+ file_out.write("%s.add_stream('%s', %s)\n" % (component, mw, value))
# If using the new syntax that allows more than one middleware
# per component
else:
for item in value:
mw = item[0]
mw = mw.lower()
- file_out.write("%s.configure_mw('%s', %s)\n" % (component, mw, item))
+ file_out.write("%s.add_stream('%s', %s)\n" % (component, mw, item))
try:
component_config.component_service
Please sign in to comment.
Something went wrong with that request. Please try again.