diff --git a/CMakeLists.txt b/CMakeLists.txt index cf0cbcb..dff5862 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -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 @@ -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}) diff --git a/launch/catch_the_bird.launch b/launch/catch_the_bird.launch index d42b491..75113a3 100644 --- a/launch/catch_the_bird.launch +++ b/launch/catch_the_bird.launch @@ -5,7 +5,7 @@ - + diff --git a/launch/complete_test.launch b/launch/complete_test.launch index 80e49ab..551cb66 100644 --- a/launch/complete_test.launch +++ b/launch/complete_test.launch @@ -5,7 +5,7 @@ - + diff --git a/launch/e_puck_line.launch b/launch/e_puck_line.launch index fb772ee..4b70feb 100644 --- a/launch/e_puck_line.launch +++ b/launch/e_puck_line.launch @@ -5,7 +5,7 @@ - + diff --git a/launch/keyboard_teleop.launch b/launch/keyboard_teleop.launch index f8ee53d..bbd680a 100644 --- a/launch/keyboard_teleop.launch +++ b/launch/keyboard_teleop.launch @@ -5,7 +5,7 @@ - + diff --git a/launch/panoramic_view_recorder.launch b/launch/panoramic_view_recorder.launch index e417256..f7a523a 100644 --- a/launch/panoramic_view_recorder.launch +++ b/launch/panoramic_view_recorder.launch @@ -5,7 +5,7 @@ - + diff --git a/launch/pioneer3at.launch b/launch/pioneer3at.launch index bdaa8fe..9c78fe4 100644 --- a/launch/pioneer3at.launch +++ b/launch/pioneer3at.launch @@ -5,9 +5,9 @@ - + - + diff --git a/launch/robot_information_parser.launch b/launch/robot_information_parser.launch index d008c7a..34f2927 100644 --- a/launch/robot_information_parser.launch +++ b/launch/robot_information_parser.launch @@ -5,7 +5,7 @@ - + diff --git a/launch/webots_ros_python.launch b/launch/webots_ros_python.launch new file mode 100644 index 0000000..1eb9272 --- /dev/null +++ b/launch/webots_ros_python.launch @@ -0,0 +1,17 @@ + + + + + + + + + + + + + + + + + diff --git a/package.xml b/package.xml index f9c562b..3dea401 100644 --- a/package.xml +++ b/package.xml @@ -1,7 +1,7 @@ webots_ros - 2.0.6 + 2.1.0 The ROS package containing examples for interfacing ROS with the standard ROS controller of Webots http://wiki.ros.org/webots_ros diff --git a/plugins/robot_windows/info/info.html b/plugins/robot_windows/info/info.html new file mode 100644 index 0000000..9f7f638 --- /dev/null +++ b/plugins/robot_windows/info/info.html @@ -0,0 +1,7 @@ + + Info window + + Show message received from the controller: + + + diff --git a/plugins/robot_windows/info/info.js b/plugins/robot_windows/info/info.js new file mode 100644 index 0000000..37d2a56 --- /dev/null +++ b/plugins/robot_windows/info/info.js @@ -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 + "'"); +} diff --git a/scripts/ros_controller.py b/scripts/ros_controller.py new file mode 100755 index 0000000..de28b94 --- /dev/null +++ b/scripts/ros_controller.py @@ -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() diff --git a/scripts/ros_python.py b/scripts/ros_python.py new file mode 100755 index 0000000..e22f963 --- /dev/null +++ b/scripts/ros_python.py @@ -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) diff --git a/src/webots_launcher.py b/scripts/webots_launcher.py similarity index 100% rename from src/webots_launcher.py rename to scripts/webots_launcher.py diff --git a/src/complete_test.cpp b/src/complete_test.cpp index 16dafb2..95f2f48 100644 --- a/src/complete_test.cpp +++ b/src/complete_test.cpp @@ -39,9 +39,11 @@ #include #include +#include #include #include #include +#include #include #include #include @@ -159,6 +161,11 @@ void cameraCallback(const sensor_msgs::Image::ConstPtr &values) { } } +void cameraRecognitionCallback(const webots_ros::RecognitionObject::ConstPtr &object) { + ROS_INFO("Camera recognition saw a '%s' (time: %d:%d).", object->model.c_str(), object->header.stamp.sec, + object->header.stamp.nsec); +} + void joystickCallback(const webots_ros::Int8Stamped::ConstPtr &value) { ROS_INFO("Joystick button pressed: %d (time: %d:%d).", value->data, value->header.stamp.sec, value->header.stamp.nsec); } @@ -259,7 +266,7 @@ void lightSensorCallback(const sensor_msgs::Illuminance::ConstPtr &value) { ROS_INFO("Light intensity is %f.", value->illuminance); } -void motorSensorCallback(const std_msgs::Float64::ConstPtr &value) { +void motorSensorCallback(const webots_ros::Float64Stamped::ConstPtr &value) { ROS_INFO("Motor sensor sent value %f.", value->data); } @@ -319,8 +326,6 @@ int main(int argc, char **argv) { //////////////////////// int mode = 0; - string controller_args; - string controller_name; string model; string path; string data; @@ -361,6 +366,22 @@ int main(int argc, char **argv) { device_list_client.shutdown(); time_step_client.call(time_step_srv); + ros::ServiceClient urdf_client = n.serviceClient(model_name + "/robot/get_urdf"); + webots_ros::get_urdf urdf_srv; + urdf_srv.request.prefix = "unique_robot_prefix_name_"; + + if (urdf_client.call(urdf_srv)) { + std::string urdf = urdf_srv.response.value; + if (urdf.find(urdf_srv.request.prefix) == std::string::npos) + ROS_ERROR("Invalid response from get_urdf."); + else + ROS_INFO("URDF has been successfully obtained."); + } else + ROS_ERROR("Failed to call service get_urdf."); + + urdf_client.shutdown(); + time_step_client.call(time_step_srv); + ros::ServiceClient get_basic_time_step_client = n.serviceClient(model_name + "/robot/get_basic_time_step"); webots_ros::get_float get_basic_time_step_srv; @@ -374,32 +395,6 @@ int main(int argc, char **argv) { get_basic_time_step_client.shutdown(); time_step_client.call(time_step_srv); - ros::ServiceClient get_controller_arguments_client = - n.serviceClient(model_name + "/robot/get_controller_arguments"); - webots_ros::get_string get_controller_arguments_srv; - - if (get_controller_arguments_client.call(get_controller_arguments_srv)) { - controller_args = get_controller_arguments_srv.response.value; - ROS_INFO("Controller arguments of %s are %s.", model_name.c_str(), controller_args.c_str()); - } else - ROS_ERROR("Failed to call service get_controller_arguments."); - - get_controller_arguments_client.shutdown(); - time_step_client.call(time_step_srv); - - ros::ServiceClient get_controller_name_client = - n.serviceClient(model_name + "/robot/get_controller_name"); - webots_ros::get_string get_controller_name_srv; - - if (get_controller_name_client.call(get_controller_name_srv)) { - controller_name = get_controller_name_srv.response.value; - ROS_INFO("Controller name of %s is %s.", model_name.c_str(), controller_name.c_str()); - } else - ROS_ERROR("Failed to call service get_controller_name."); - - get_controller_name_client.shutdown(); - time_step_client.call(time_step_srv); - ros::ServiceClient robot_get_custom_data_client = n.serviceClient(model_name + "/robot/get_custom_data"); webots_ros::get_string robot_get_custom_data_srv; @@ -724,6 +719,33 @@ int main(int argc, char **argv) { get_info_client.shutdown(); time_step_client.call(time_step_srv); + // camera recognition enable + ros::ServiceClient enable_camera_recognition_client; + webots_ros::set_int camera_recognition_srv; + ros::Subscriber sub_camera_recognition; + + enable_camera_recognition_client = n.serviceClient(model_name + "/camera/recognition_enable"); + camera_recognition_srv.request.value = TIME_STEP; + if (enable_camera_recognition_client.call(camera_recognition_srv) && camera_recognition_srv.response.success) { + ROS_INFO("Camera recognition enabled."); + sub_camera_recognition = n.subscribe(model_name + "/camera/recognition_objects", 1, cameraRecognitionCallback); + ROS_INFO("Topic for camera recognition initialized."); + while (sub_camera_recognition.getNumPublishers() == 0) { + ros::spinOnce(); + time_step_client.call(time_step_srv); + } + ROS_INFO("Topic for camera recognition connected."); + } else { + if (camera_recognition_srv.response.success == -1) + ROS_ERROR("Sampling period is not valid."); + ROS_ERROR("Failed to enable camera recognition."); + return 1; + } + + sub_camera_recognition.shutdown(); + enable_camera_recognition_client.shutdown(); + time_step_client.call(time_step_srv); + // camera_save_image ros::ServiceClient save_image_client = n.serviceClient(model_name + "/camera/save_image"); webots_ros::save_image save_image_srv; @@ -816,6 +838,18 @@ int main(int argc, char **argv) { return 1; } + ros::ServiceClient lookup_table_accelerometer_client; + webots_ros::get_float_array lookup_table_accelerometer_srv; + lookup_table_accelerometer_client = + n.serviceClient(model_name + "/accelerometer/get_lookup_table"); + if (lookup_table_accelerometer_client.call(lookup_table_accelerometer_srv)) + ROS_INFO("Accelerometer lookup table size = %lu.", lookup_table_accelerometer_srv.response.value.size()); + else + ROS_ERROR("Failed to get the lookup table of 'accelerometer'."); + if (lookup_table_accelerometer_srv.response.value.size() != 0) + ROS_ERROR("Size of lookup table of 'accelerometer' is wrong."); + lookup_table_accelerometer_client.shutdown(); + sub_accelerometer_32.shutdown(); set_accelerometer_client.shutdown(); time_step_client.call(time_step_srv); @@ -911,6 +945,17 @@ int main(int argc, char **argv) { return 1; } + ros::ServiceClient lookup_table_compass_client; + webots_ros::get_float_array lookup_table_compass_srv; + lookup_table_compass_client = n.serviceClient(model_name + "/compass/get_lookup_table"); + if (lookup_table_compass_client.call(lookup_table_compass_srv)) + ROS_INFO("Compass lookup table size = %lu.", lookup_table_compass_srv.response.value.size()); + else + ROS_ERROR("Failed to get the lookup table of 'compass'."); + if (lookup_table_compass_srv.response.value.size() != 0) + ROS_ERROR("Size of lookup table of 'compass' is wrong."); + lookup_table_compass_client.shutdown(); + sub_compass_32.shutdown(); time_step_client.call(time_step_srv); @@ -1363,6 +1408,19 @@ int main(int argc, char **argv) { ROS_ERROR("Failed to get the aperture of 'distance_sensor'."); aperture_distance_sensor_client.shutdown(); + ros::ServiceClient lookup_table_distance_sensor_client; + webots_ros::get_float_array lookup_table_distance_sensor_srv; + lookup_table_distance_sensor_client = + n.serviceClient(model_name + "/distance_sensor/get_lookup_table"); + if (lookup_table_distance_sensor_client.call(lookup_table_distance_sensor_srv)) + ROS_INFO("Distance_sensor lookup table size = %lu.", lookup_table_distance_sensor_srv.response.value.size()); + else + ROS_ERROR("Failed to get the lookup table of 'distance_sensor'."); + if (lookup_table_distance_sensor_srv.response.value.size() != 6) + ROS_ERROR("Size of lookup table of 'distance_sensor' is wrong, expected 0 got %lu.", + lookup_table_distance_sensor_srv.response.value.size()); + lookup_table_distance_sensor_client.shutdown(); + distance_sensor_srv.request.value = 32; if (set_distance_sensor_client.call(distance_sensor_srv) && distance_sensor_srv.response.success) { ROS_INFO("Distance_sensor enabled."); @@ -1563,6 +1621,17 @@ int main(int argc, char **argv) { } sub_gyro_32.shutdown(); + ros::ServiceClient lookup_table_gyro_client; + webots_ros::get_float_array lookup_table_gyro_srv; + lookup_table_gyro_client = n.serviceClient(model_name + "/gyro/get_lookup_table"); + if (lookup_table_gyro_client.call(lookup_table_gyro_srv)) + ROS_INFO("Gyro lookup table size = %lu.", lookup_table_gyro_srv.response.value.size()); + else + ROS_ERROR("Failed to get the lookup table of 'gyro'."); + if (lookup_table_gyro_srv.response.value.size() != 0) + ROS_ERROR("Size of lookup table of 'gyro' is wrong."); + lookup_table_gyro_client.shutdown(); + time_step_client.call(time_step_srv); sampling_period_gyro_client.call(sampling_period_gyro_srv); @@ -1608,6 +1677,18 @@ int main(int argc, char **argv) { sub_inertial_unit_32.shutdown(); + ros::ServiceClient lookup_table_inertial_unit_client; + webots_ros::get_float_array lookup_table_inertial_unit_srv; + lookup_table_inertial_unit_client = + n.serviceClient(model_name + "/inertial_unit/get_lookup_table"); + if (lookup_table_inertial_unit_client.call(lookup_table_inertial_unit_srv)) + ROS_INFO("Inertial unit lookup table size = %lu.", lookup_table_inertial_unit_srv.response.value.size()); + else + ROS_ERROR("Failed to get the lookup table of 'inertial_unit'."); + if (lookup_table_inertial_unit_srv.response.value.size() != 0) + ROS_ERROR("Size of lookup table of 'inertial_unit' is wrong."); + lookup_table_inertial_unit_client.shutdown(); + time_step_client.call(time_step_srv); sampling_period_inertial_unit_client.call(sampling_period_inertial_unit_srv); @@ -1783,6 +1864,18 @@ int main(int argc, char **argv) { sub_light_sensor_32.shutdown(); + ros::ServiceClient lookup_table_light_sensor_client; + webots_ros::get_float_array lookup_table_light_sensor_srv; + lookup_table_light_sensor_client = + n.serviceClient(model_name + "/light_sensor/get_lookup_table"); + if (lookup_table_light_sensor_client.call(lookup_table_light_sensor_srv)) + ROS_INFO("Light sensor lookup table size = %lu.", lookup_table_light_sensor_srv.response.value.size()); + else + ROS_ERROR("Failed to get the lookup table of 'light_sensor'."); + if (lookup_table_light_sensor_srv.response.value.size() != 6) + ROS_ERROR("Size of lookup table of 'light_sensor' is wrong."); + lookup_table_light_sensor_client.shutdown(); + time_step_client.call(time_step_srv); sampling_period_light_sensor_client.call(sampling_period_light_sensor_srv); @@ -2067,6 +2160,48 @@ int main(int argc, char **argv) { get_max_torque_client.shutdown(); time_step_client.call(time_step_srv); + + ros::ServiceClient set_motor_feedback_client; + webots_ros::set_int motor_feedback_srv; + ros::Subscriber sub_motor_feedback_32; + set_motor_feedback_client = + n.serviceClient(model_name + "/rotational_motor/torque_feedback_sensor/enable"); + + ros::ServiceClient sampling_period_motor_feedback_client; + webots_ros::get_int sampling_period_motor_feedback_srv; + sampling_period_motor_feedback_client = + n.serviceClient(model_name + "/rotational_motor/torque_feedback_sensor/get_sampling_period"); + + motor_feedback_srv.request.value = 32; + if (set_motor_feedback_client.call(motor_feedback_srv) && motor_feedback_srv.response.success) { + ROS_INFO("Motor feedback enabled."); + sub_motor_feedback_32 = n.subscribe(model_name + "/rotational_motor/torque_feedback", 1, motorSensorCallback); + while (sub_motor_feedback_32.getNumPublishers() == 0) { + ros::spinOnce(); + time_step_client.call(time_step_srv); + } + } else { + if (!motor_feedback_srv.response.success) + ROS_ERROR("Sampling period is not valid."); + ROS_ERROR("Failed to enable motor_feedback."); + return 1; + } + + sub_motor_feedback_32.shutdown(); + + time_step_client.call(time_step_srv); + + sampling_period_motor_feedback_client.call(sampling_period_motor_feedback_srv); + ROS_INFO("Motor feedback is enabled with a sampling period of %d.", sampling_period_motor_feedback_srv.response.value); + + time_step_client.call(time_step_srv); + + sampling_period_motor_feedback_client.call(sampling_period_motor_feedback_srv); + ROS_INFO("Motor feedback is disabled (sampling period is %d).", sampling_period_motor_feedback_srv.response.value); + + set_motor_feedback_client.shutdown(); + sampling_period_motor_feedback_client.shutdown(); + time_step_client.call(time_step_srv); time_step_client.call(time_step_srv); ////////////////////// @@ -2474,6 +2609,18 @@ int main(int argc, char **argv) { sub_touch_sensor_32.shutdown(); + ros::ServiceClient lookup_table_touch_sensor_client; + webots_ros::get_float_array lookup_table_touch_sensor_srv; + lookup_table_touch_sensor_client = + n.serviceClient(model_name + "/touch_sensor/get_lookup_table"); + if (lookup_table_touch_sensor_client.call(lookup_table_touch_sensor_srv)) + ROS_INFO("Touch sensor lookup table size = %lu.", lookup_table_touch_sensor_srv.response.value.size()); + else + ROS_ERROR("Failed to get the lookup table of 'touch_sensor'."); + if (lookup_table_touch_sensor_srv.response.value.size() != 6) + ROS_ERROR("Size of lookup table of 'touch_sensor' is wrong."); + lookup_table_touch_sensor_client.shutdown(); + time_step_client.call(time_step_srv); sampling_period_touch_sensor_client.call(sampling_period_touch_sensor_srv); @@ -2763,6 +2910,7 @@ int main(int argc, char **argv) { supervisor_node_get_field_srv.request.node = root_node; supervisor_node_get_field_srv.request.fieldName = "children"; + supervisor_node_get_field_srv.request.proto = 0; supervisor_node_get_field_client.call(supervisor_node_get_field_srv); uint64_t field = supervisor_node_get_field_srv.response.field; @@ -2858,6 +3006,7 @@ int main(int argc, char **argv) { // supervisor_node_get_from_id supervisor_get_from_def_srv.request.name = "CONE"; + supervisor_get_from_def_srv.request.proto = 0; supervisor_get_from_def_client.call(supervisor_get_from_def_srv); uint64_t cone_node = 0; if (supervisor_get_from_def_srv.response.node != 0) { diff --git a/src/e_puck_line.cpp b/src/e_puck_line.cpp index 94c986a..f1415d4 100644 --- a/src/e_puck_line.cpp +++ b/src/e_puck_line.cpp @@ -577,12 +577,10 @@ int main(int argc, char **argv) { ROS_ERROR("Failed to call service time_step to update robot's time step."); // get sensors value - if (nStep % 1 == 0) { - countDist = 0; - countGnd = 0; - while (countDist < NB_DIST_SENS || countGnd < NB_GROUND_SENS) - ros::spinOnce(); - } + countDist = 0; + countGnd = 0; + while (countDist < NB_DIST_SENS || countGnd < NB_GROUND_SENS) + ros::spinOnce(); // Speed initialization speed[LEFT] = 0; diff --git a/srv/get_float_array.srv b/srv/get_float_array.srv new file mode 100644 index 0000000..4c468b9 --- /dev/null +++ b/srv/get_float_array.srv @@ -0,0 +1,3 @@ +bool ask +--- +float64[] value diff --git a/srv/get_urdf.srv b/srv/get_urdf.srv new file mode 100644 index 0000000..4b150b7 --- /dev/null +++ b/srv/get_urdf.srv @@ -0,0 +1,3 @@ +string prefix +--- +string value diff --git a/srv/node_get_field.srv b/srv/node_get_field.srv index 9c311c0..6402ab3 100644 --- a/srv/node_get_field.srv +++ b/srv/node_get_field.srv @@ -1,4 +1,5 @@ uint64 node string fieldName +bool proto --- uint64 field diff --git a/srv/node_is_proto.srv b/srv/node_is_proto.srv new file mode 100644 index 0000000..7e5aedb --- /dev/null +++ b/srv/node_is_proto.srv @@ -0,0 +1,3 @@ +uint64 node +--- +bool value diff --git a/srv/supervisor_get_from_def.srv b/srv/supervisor_get_from_def.srv index 795abce..c74bc32 100644 --- a/srv/supervisor_get_from_def.srv +++ b/srv/supervisor_get_from_def.srv @@ -1,3 +1,4 @@ string name +uint64 proto --- uint64 node diff --git a/worlds/.catch_the_bird.wbproj b/worlds/.catch_the_bird.wbproj new file mode 100644 index 0000000..5ea4386 --- /dev/null +++ b/worlds/.catch_the_bird.wbproj @@ -0,0 +1,10 @@ +Webots Project File version R2020b +perspectives: 000000ff00000000fd00000003000000000000000000000000fc0100000002fc00000000ffffffff0000000000fffffffc0200000001fb00000012005300630065006e0065005400720065006501000000190000033d0000000000000000fb0000001a0044006f00630075006d0065006e0074006100740069006f006e0000000000ffffffff0000006900ffffff00000001000002ec0000025efc0200000001fb0000001400540065007800740045006400690074006f007200000000190000025e0000003f00ffffff00000003000004e20000005afc0100000002fb0000000e0043006f006e0073006f006c006501000000000000073f0000000000000000fb0000001a0043006f006e0073006f006c00650041006c006c0041006c006c0100000000000004e20000006900ffffff000004e20000015700000001000000020000000100000008fc00000000 +simulationViewPerspectives: 000000ff00000001000000020000016c000002060100000002010000000101 +sceneTreePerspectives: 000000ff0000000100000002000000c0000000fc0100000002010000000201 +maximizedDockId: -1 +centralWidgetVisible: 1 +orthographicViewHeight: 1 +textFiles: -1 +consoles: Console:All:All +renderingDevicePerspectives: robot:range-finder;1;1;0;0 diff --git a/worlds/.complete_test.wbproj b/worlds/.complete_test.wbproj new file mode 100644 index 0000000..42abe8d --- /dev/null +++ b/worlds/.complete_test.wbproj @@ -0,0 +1,13 @@ +Webots Project File version R2020b +perspectives: 000000ff00000000fd00000003000000000000018f00000482fc0100000004fc00000000ffffffff0000000000fffffffc0200000001fb00000012005300630065006e0065005400720065006501000000190000033d0000000000000000fb0000002c0052006f0062006f0074003a002000660075006c006c005f00730075007000650072007600690073006f007201000000000000018f0000000000000000fb0000001e00480074006d006c0052006f0062006f007400570069006e0064006f007701000000000000018f0000005400fffffffb0000001a0044006f00630075006d0065006e0074006100740069006f006e0000000000ffffffff0000005400ffffff00000001000001ed000003a2fc0200000001fb0000001400540065007800740045006400690074006f00720100000000000003a20000003c00ffffff00000003000005aa000000dafc0100000001fb0000000e0043006f006e0073006f006c00650100000195000005aa0000005400ffffff000003b7000003a200000004000000040000000100000008fc00000000 +simulationViewPerspectives: 000000ff000000010000000200000170000003490100000006010000000101 +sceneTreePerspectives: 000000ff0000000100000002000000c0000000fc0100000006010000000201 +maximizedDockId: -1 +centralWidgetVisible: 1 +orthographicViewHeight: 1 +textFiles: -1 +robotWindow: full_supervisor +consoles: Console:All:All +renderingDevicePerspectives: full_supervisor:camera;1;1;0;0 +renderingDevicePerspectives: full_supervisor:display;1;1;0;0 +renderingDevicePerspectives: full_supervisor:range_finder;1;1;0;0 diff --git a/worlds/.e-puck_line.wbproj b/worlds/.e-puck_line.wbproj new file mode 100644 index 0000000..63be202 --- /dev/null +++ b/worlds/.e-puck_line.wbproj @@ -0,0 +1,11 @@ +Webots Project File version R2020b +perspectives: 000000ff00000000fd00000003000000000000016c0000033dfc0200000001fb00000012005300630065006e0065005400720065006500000000190000033d0000000000000000000000010000016200000309fc0200000001fb0000001400540065007800740045006400690074006f00720100000019000003090000003e00ffffff000000030000073f000000e2fc0100000001fb0000000e0043006f006e0073006f006c006501000000000000073f0000005a00ffffff000005d70000030900000004000000040000000100000008fc00000000 +simulationViewPerspectives: 000000ff00000001000000020000016c000002850100000006010000000101 +sceneTreePerspectives: 000000ff0000000100000002000000c0000000a80100000006010000000201 +minimizedPerspectives: 000000ff00000000fd00000003000000000000016c0000033dfc0200000001fb00000012005300630065006e0065005400720065006501000000190000033d0000018500ffffff000000010000033f000001ebfc0200000001fb0000001400540065007800740045006400690074006f00720100000019000001eb000000ab00ffffff00000003000003ed0000014cfc0100000001fb0000000e0043006f006e0073006f006c00650100000172000003ed0000004e00ffffff000000a8000001eb00000004000000040000000100000008fc00000000 +maximizedDockId: -1 +centralWidgetVisible: 1 +orthographicViewHeight: 1 +textFiles: -1 +consoles: Console:All:All +renderingDevicePerspectives: e-puck:camera;0;1;0.0229397;0.0283149 diff --git a/worlds/.keyboard_teleop.wbproj b/worlds/.keyboard_teleop.wbproj new file mode 100644 index 0000000..4737461 --- /dev/null +++ b/worlds/.keyboard_teleop.wbproj @@ -0,0 +1,9 @@ +Webots Project File version R2020b +perspectives: 000000ff00000000fd00000003000000000000016c0000033dfc0200000001fb00000012005300630065006e0065005400720065006501000000190000033d000000000000000000000001000001e100000258fc0200000001fb0000001400540065007800740045006400690074006f00720100000019000002580000003e00ffffff000000030000073f00000193fc0100000001fb0000000e0043006f006e0073006f006c006501000000000000073f0000005a00ffffff000005580000025800000001000000020000000100000008fc00000000 +simulationViewPerspectives: 000000ff00000001000000020000016c000002060100000006010000000101 +sceneTreePerspectives: 000000ff0000000100000002000000c0000000a80100000006010000000201 +maximizedDockId: -1 +centralWidgetVisible: 1 +orthographicViewHeight: 1 +textFiles: -1 +consoles: Console:All:All diff --git a/worlds/.panoramic_view_recorder.wbproj b/worlds/.panoramic_view_recorder.wbproj new file mode 100644 index 0000000..c532096 --- /dev/null +++ b/worlds/.panoramic_view_recorder.wbproj @@ -0,0 +1,11 @@ +Webots Project File version R2020b +perspectives: 000000ff00000000fd00000003000000000000000000000000fc0100000001fb0000001a0044006f00630075006d0065006e0074006100740069006f006e0000000000ffffffff0000005400ffffff000000010000012e000003a2fc0200000001fb0000001400540065007800740045006400690074006f00720100000000000003a20000003c00ffffff000000030000073f000000dafc0100000001fb0000000e0043006f006e0073006f006c006501000000000000073f0000005400ffffff0000060b000003a200000001000000020000000100000008fc00000000 +simulationViewPerspectives: 000000ff00000001000000020000016c000004a00100000006010000000101 +sceneTreePerspectives: 000000ff0000000100000002000000c0000001120100000006010000000201 +maximizedDockId: -1 +centralWidgetVisible: 1 +orthographicViewHeight: 1 +textFiles: -1 +consoles: Console:All:All +renderingDevicePerspectives: NAO:CameraBottom;0;1;0;0.570423 +renderingDevicePerspectives: NAO:CameraTop;0;1;0;0.00229358 diff --git a/worlds/.pioneer3at.wbproj b/worlds/.pioneer3at.wbproj new file mode 100644 index 0000000..20608b5 --- /dev/null +++ b/worlds/.pioneer3at.wbproj @@ -0,0 +1,10 @@ +Webots Project File version R2020b +perspectives: 000000ff00000000fd00000003000000000000000000000000fc0100000001fb0000001a0044006f00630075006d0065006e0074006100740069006f006e0000000000ffffffff0000005400ffffff000000010000012e000002d9fc0200000001fb0000001400540065007800740045006400690074006f00720000000019000002d9000000a200ffffff000000030000073f000000bbfc0100000001fb0000000e0043006f006e0073006f006c006501000000000000073f0000005400ffffff0000073f000003c100000001000000020000000100000008fc00000000 +simulationViewPerspectives: 000000ff00000001000000020000011e000004db0100000006010000000101 +sceneTreePerspectives: 000000ff0000000100000002000000c0000001240100000006010000000201 +maximizedDockId: -1 +centralWidgetVisible: 1 +orthographicViewHeight: 1 +textFiles: -1 +consoles: Console:All:All +renderingDevicePerspectives: Pioneer 3-AT:camera;1;1;0;0 diff --git a/worlds/.ros_python.wbproj b/worlds/.ros_python.wbproj new file mode 100644 index 0000000..d77a25d --- /dev/null +++ b/worlds/.ros_python.wbproj @@ -0,0 +1,10 @@ +Webots Project File version R2020b +perspectives: 000000ff00000000fd00000003000000000000000000000000fc0100000001fb0000001a0044006f00630075006d0065006e0074006100740069006f006e0000000000ffffffff0000006900ffffff00000001000001c900000375fc0200000001fb0000001400540065007800740045006400690074006f00720100000000000003750000008900ffffff000000030000073f00000093fc0100000001fb0000000e0043006f006e0073006f006c006501000000000000073f0000006900ffffff000005740000037500000001000000020000000100000008fc00000000 +simulationViewPerspectives: 000000ff000000010000000200000100000005210100000002010000000100 +sceneTreePerspectives: 000000ff0000000100000002000002aa000000fa0100000002010000000200 +maximizedDockId: -1 +centralWidgetVisible: 1 +orthographicViewHeight: 1 +textFiles: 0 "scripts/ros_python.py" "scripts/ros_controller.py" +globalOptionalRendering: DistanceSensorRays +consoles: Console:All:All diff --git a/worlds/catch_the_bird.wbt b/worlds/catch_the_bird.wbt new file mode 100644 index 0000000..66b6b9f --- /dev/null +++ b/worlds/catch_the_bird.wbt @@ -0,0 +1,291 @@ +#VRML_SIM R2020b utf8 +WorldInfo { + coordinateSystem "NUE" +} +Viewpoint { + orientation -0.104674958073239 -0.9575576164575551 -0.26856389242876866 2.60605 + position -1.59084 1.87221 -2.53085 +} +TexturedBackground { +} +TexturedBackgroundLight { +} +RectangleArena { +} +Robot { + translation -0.1 0.09 0 + children [ + HingeJoint { + jointParameters HingeJointParameters { + axis 0 1 0 + } + device [ + RotationalMotor { + name "motor" + } + ] + endPoint Solid { + translation 0 0.12 -0.03 + rotation 1 0 0 1.57 + children [ + RangeFinder { + translation 0 -0.05 0 + rotation 1 0 0 -1.57 + } + Shape { + appearance PBRAppearance { + roughness 1 + metalness 0 + } + geometry Cylinder { + height 0.1 + radius 0.03 + } + } + ] + boundingObject Cylinder { + height 0.1 + radius 0.03 + } + physics Physics { + } + } + } + Shape { + appearance PBRAppearance { + roughness 1 + metalness 0 + } + geometry Cylinder { + height 0.18 + radius 0.05 + } + } + ] + boundingObject Cylinder { + height 0.18 + radius 0.05 + } + physics Physics { + } + locked TRUE + controller "ros" +} +Solid { + translation 0.3 0.1 0 + children [ + Solid { + translation 0 -0.09 0 + children [ + Shape { + appearance PBRAppearance { + baseColor 0.588235 0.196078 0 + roughness 1 + metalness 0 + } + geometry Box { + size 0.1 0.02 0.02 + } + } + ] + boundingObject Box { + size 0.1 0.02 0.02 + } + physics Physics { + } + } + Solid { + translation 0 -0.09 0 + children [ + Shape { + appearance PBRAppearance { + baseColor 0.588235 0.196078 0 + roughness 1 + metalness 0 + } + geometry Box { + size 0.02 0.02 0.1 + } + } + ] + name "solid(1)" + boundingObject Box { + size 0.02 0.02 0.1 + } + physics Physics { + } + } + Solid { + translation -0.02 0.16 0 + rotation 0 0 1 1 + children [ + Solid { + translation 0.015 0 0 + children [ + Shape { + appearance PBRAppearance { + baseColor 0.996078 1 0 + roughness 1 + metalness 0 + } + geometry Box { + size 0.005 0.07 0.15 + } + } + ] + name "wings" + boundingObject Box { + size 0.005 0.07 0.15 + } + physics Physics { + } + } + Solid { + translation 0 0.06 0 + children [ + Solid { + translation -0.01 0.01 0 + rotation 0 0 1 -0.7 + children [ + Shape { + appearance PBRAppearance { + baseColor 1 0 0 + roughness 1 + metalness 0 + } + geometry Box { + size 0.04 0.008 0.008 + } + } + ] + name "nose" + boundingObject Box { + size 0.04 0.008 0.008 + } + physics Physics { + } + } + Shape { + appearance PBRAppearance { + baseColor 0.913725 0.682353 0 + roughness 1 + metalness 0 + } + geometry Sphere { + radius 0.025 + } + } + ] + name "head" + boundingObject Sphere { + radius 0.025 + } + physics Physics { + } + } + Solid { + translation -0.02 -0.03 -0.025 + rotation 0 0 1 -1 + children [ + Shape { + appearance PBRAppearance { + baseColor 0 0 0 + roughness 1 + metalness 0 + } + geometry Box { + size 0.015 0.05 0.015 + } + } + ] + name "right_leg" + boundingObject Box { + size 0.015 0.05 0.015 + } + physics Physics { + } + } + Solid { + translation -0.02 -0.03 0.025 + rotation 0 0 1 -1 + children [ + Shape { + appearance PBRAppearance { + baseColor 0 0 0 + roughness 1 + metalness 0 + } + geometry Box { + size 0.015 0.05 0.015 + } + } + ] + name "left_leg" + boundingObject Box { + size 0.015 0.05 0.015 + } + physics Physics { + } + } + Shape { + appearance PBRAppearance { + baseColor 0.772549 0 0 + roughness 1 + metalness 0 + } + geometry Capsule { + height 0.07 + radius 0.02 + } + } + ] + name "body" + boundingObject Capsule { + height 0.07 + radius 0.02 + subdivision 16 + } + physics Physics { + } + locked TRUE + } + Solid { + translation 0 0.1 0 + children [ + Shape { + appearance PBRAppearance { + baseColor 0.588235 0.196078 0 + roughness 1 + metalness 0 + } + geometry Box { + size 0.02 0.02 0.2 + } + } + ] + name "solid(2)" + boundingObject Box { + size 0.02 0.02 0.2 + } + physics Physics { + } + } + Shape { + appearance PBRAppearance { + baseColor 0.588235 0.196078 0 + roughness 1 + metalness 0 + } + geometry Box { + size 0.02 0.2 0.02 + } + } + ] + name "pillar" + boundingObject Box { + size 0.02 0.2 0.02 + } + physics Physics { + } + locked TRUE +} diff --git a/worlds/complete_test.wbt b/worlds/complete_test.wbt new file mode 100644 index 0000000..acadfb9 --- /dev/null +++ b/worlds/complete_test.wbt @@ -0,0 +1,282 @@ +#VRML_SIM R2020b utf8 +WorldInfo { + coordinateSystem "NUE" +} +Viewpoint { + orientation -0.6194591910547989 0.7334082212488283 0.27996909047672397 0.888923 + position 1.67801 1.75743 2.04642 +} +TexturedBackground { +} +TexturedBackgroundLight { +} +DEF GROUND RectangleArena { +} +Solid { + translation 0.182984 0.05 0.12186 + rotation 0 -1 0 0.934348 + children [ + Shape { + appearance PBRAppearance { + baseColor 0.8 0.8 0.8 + roughness 1 + metalness 0 + } + geometry Box { + size 0.1 0.1 0.2 + } + } + ] + boundingObject Box { + size 0.1 0.1 0.2 + } + physics Physics { + } +} +DEF CONE Solid { + translation 0.240484 0.1 -0.258217 + children [ + Shape { + appearance PBRAppearance { + baseColor 0 0.0392157 0.8 + roughness 0.8760235838 + metalness 0 + emissiveColor 0.027451 0.027451 0.968627 + } + geometry Cone { + bottomRadius 0.08 + height 0.2 + } + } + ] + name "solid(1)" +} +DEF RADAR_TARGET Solid { + translation 0 0 -1.86 + children [ + Shape { + appearance PBRAppearance { + baseColor 0 1 0 + roughness 1 + metalness 0 + } + geometry DEF SPHERE Sphere { + radius 0.1 + } + } + ] + name "solid(2)" + boundingObject USE SPHERE + radarCrossSection 1 +} +Robot { + translation 0 0.1 0 + children [ + SliderJoint { + device [ + Brake { + name "my_brake" + } + LinearMotor { + name "linear_motor" + maxPosition 100 + } + ] + endPoint Solid { + translation -0.12 0 0 + rotation 1 0 0 1.57 + children [ + Shape { + appearance PBRAppearance { + baseColor 1 0 0.0156863 + roughness 0.6992117618 + metalness 0 + } + geometry Box { + size 0.02 0.25 0.08 + } + } + ] + name "solid1" + boundingObject Box { + size 0.02 0.25 0.08 + } + } + } + HingeJoint { + device [ + PositionSensor { + name "position_sensor" + } + ] + endPoint Solid { + translation 0 0 -0.15 + rotation 1 0 0 0 + children [ + Shape { + appearance PBRAppearance { + baseColor 0.8 0.8 0.8 + roughness 1 + metalness 0 + } + geometry Cylinder { + height 0.1 + radius 0.05 + } + } + ] + boundingObject Cylinder { + height 0.1 + radius 0.05 + } + } + } + HingeJoint { + device [ + RotationalMotor { + name "rotational_motor" + acceleration 5 + maxVelocity 2 + } + ] + endPoint DEF TEST2 Solid { + translation 0.12 0.05 0 + rotation 1 0 0 0 + children [ + Shape { + appearance PBRAppearance { + baseColor 1 0 0.0156863 + roughness 0.6992117618 + metalness 0 + } + geometry Box { + size 0.02 0.25 0.08 + } + } + ] + name "solid(1)" + boundingObject Box { + size 0.02 0.25 0.08 + } + physics Physics { + } + } + } + Camera { + translation 0.14 0 0 + model "camera model" + focus Focus { + focalDistance 0.2 + focalLength 0.3 + maxFocalDistance 0.4 + minFocalDistance 0.1 + } + zoom Zoom { + maxFieldOfView 1.51 + minFieldOfView 0.49 + } + recognition Recognition { + } + } + RangeFinder { + translation 0.14 0 0 + name "range_finder" + model "range-finder model" + } + Lidar { + } + DEF TEST Compass { + } + Connector { + } + Display { + } + DistanceSensor { + name "distance_sensor" + } + Emitter { + range 100 + channel 3 + } + GPS { + } + Gyro { + physics Physics { + density -1 + mass 1 + centerOfMass [ + 0 0 0 + ] + inertiaMatrix [ + 1 1 1 + 0 0 0 + ] + } + } + InertialUnit { + name "inertial_unit" + } + LED { + translation 0.1 0.05 0.1 + children [ + Shape { + appearance PBRAppearance { + roughness 1 + metalness 0 + } + geometry Sphere { + radius 0.02 + } + } + ] + boundingObject Sphere { + radius 0.02 + } + color [ + 0.666667 1 1 + ] + } + LightSensor { + name "light_sensor" + } + Pen { + } + Receiver { + } + TouchSensor { + name "touch_sensor" + } + Shape { + appearance PBRAppearance { + baseColor 0.8 0 0.0117647 + roughness 1 + metalness 0 + } + geometry Box { + size 0.2 0.2 0.2 + } + } + Accelerometer { + } + Radar { + maxRange 2 + } + ] + name "full_supervisor" + model "all_devices" + boundingObject Box { + size 0.2 0.2 0.2 + } + controller "ros" + controllerArgs [ + "--name=my_robot" + "--clock" + "--synchronize" + ] + customData "INITIAL" + supervisor TRUE + battery [ + 10, 10, 2 + ] + window "info" +} diff --git a/worlds/e-puck_line.wbt b/worlds/e-puck_line.wbt new file mode 100644 index 0000000..d29aac4 --- /dev/null +++ b/worlds/e-puck_line.wbt @@ -0,0 +1,88 @@ +#VRML_SIM R2020b utf8 +WorldInfo { + coordinateSystem "NUE" +} +Viewpoint { + orientation 0.8817326747174138 0.4433808364310757 0.16112394055929466 5.50129 + position -0.45881 0.996783 1.25076 +} +TexturedBackground { +} +TexturedBackgroundLight { +} +RectangleArena { + floorSize 0.9 0.9 + floorTileSize 0.9 0.9 + floorAppearance PBRAppearance { + baseColorMap ImageTexture { + url [ + "textures/floor.png" + ] + } + roughness 1 + metalness 0 + } + wallHeight 0.05 +} +DEF OBSTACLE1 Solid { + translation 0.0871577 0.025 -0.192401 + children [ + Shape { + appearance PBRAppearance { + baseColor 1 0.1 0.3 + roughness 1 + metalness 0 + } + geometry DEF BOX1 Box { + size 0.05 0.05 0.05 + } + } + ] + name "red box" + boundingObject USE BOX1 +} +DEF OBSTACLE2 Solid { + translation -0.0677406 0.025 -0.0327153 + rotation 0 1 0 4.08383 + children [ + Shape { + appearance PBRAppearance { + baseColor 1 0.501961 1 + roughness 1 + metalness 0 + } + geometry DEF BOX2 Box { + size 0.08 0.05 0.08 + } + } + ] + name "pink box" + boundingObject USE BOX2 +} +DEF OBSTACLE3 Solid { + translation 0.31759 0.025 0.250604 + rotation 0 1 0 13.7261 + children [ + Shape { + appearance PBRAppearance { + baseColor 0.501961 0.501961 0.501961 + roughness 1 + metalness 0 + } + geometry DEF BOX3 Box { + size 0.2 0.05 0.05 + } + } + ] + name "gray box" + boundingObject USE BOX3 +} +DEF EPUCK E-puck { + translation 0.080305 0 0.171886 + rotation 0 1 0 1.5 + controller "ros" + groundSensorsSlot [ + E-puckGroundSensors { + } + ] +} diff --git a/worlds/keyboard_teleop.wbt b/worlds/keyboard_teleop.wbt new file mode 100644 index 0000000..6ea6d87 --- /dev/null +++ b/worlds/keyboard_teleop.wbt @@ -0,0 +1,30 @@ +#VRML_SIM R2020b utf8 +WorldInfo { + coordinateSystem "NUE" +} +Viewpoint { + orientation 0.702730921913247 0.6961909226399652 0.146585983711513 5.45898 + position -5.30367 5.63958 6.90061 +} +TexturedBackground { +} +TexturedBackgroundLight { +} +RectangleArena { + floorSize 4 4 + wallThickness 0.1 + wallHeight 0.5 +} +CardboardBox { + translation 1.31407 0.3 -0.444198 +} +CardboardBox { + translation 0.133486 0.3 -1.17773 + name "cardboard box(1)" +} +WoodenBox { + translation -0.797045 0.3 1.02408 +} +DEF PIONEER_3DX Pioneer3dx { + controller "ros" +} diff --git a/worlds/panoramic_view_recorder.wbt b/worlds/panoramic_view_recorder.wbt new file mode 100644 index 0000000..d5d03ed --- /dev/null +++ b/worlds/panoramic_view_recorder.wbt @@ -0,0 +1,21 @@ +#VRML_SIM R2020b utf8 +WorldInfo { + coordinateSystem "NUE" +} +Viewpoint { + orientation 0 1 0 0 + position 0 0.35 1.5 +} +TexturedBackground { +} +TexturedBackgroundLight { +} +Robot { + controller "ros" + supervisor TRUE +} +Floor { +} +Nao { + controller "void" +} diff --git a/worlds/pioneer3at.wbt b/worlds/pioneer3at.wbt new file mode 100644 index 0000000..08d41e5 --- /dev/null +++ b/worlds/pioneer3at.wbt @@ -0,0 +1,1978 @@ +#VRML_SIM R2020b utf8 +WorldInfo { + info [ + "Pioneer 3AT robot (Adept MobileRobots)." + "This all terrain four wheels drive robot is equipped with a Sick LMS 291 lidar." + "You should use the ros node 'pioneer3at' to control the robot." + ] + title "Pioneer 3AT" + coordinateSystem "NUE" + lineScale 0.5 +} +Viewpoint { + orientation -0.9998746704111705 0.010987887687598594 -0.011397797783707198 0.8335816938124668 + position 8.637520000000002 43.2864 39.212999999999994 + follow "Pioneer 3-AT" +} +TexturedBackground { +} +TexturedBackgroundLight { +} +Floor { + size 60 60 + tileSize 1 1 + appearance ThreadMetalPlate { + } +} +Carpet { + translation 7.57085 -4.52971e-14 -0.83 +} +Carpet { + translation 7.57085 -4.52971e-14 -2.42019 + name "carpet(1)" +} +DEF EXTERNAL_WALL Wall { + translation 0 0 -30 + size 22.4 2.4 0.2 +} +DEF EXTERNAL_WALL Wall { + translation 18 0 -30 + name "wall(1)" + size 10.4 2.4 0.2 +} +DEF EXTERNAL_WALL Wall { + translation -18 0 -30 + name "wall(2)" + size 10.4 2.4 0.2 +} +DEF EXTERNAL_WALL Wall { + translation 27.45 0 -30 + name "wall(3)" + size 5.3 2.4 0.2 +} +DEF EXTERNAL_WALL Wall { + translation -27.45 0 -30 + name "wall(4)" + size 5.3 2.4 0.2 +} +DEF DOUBLE_WINDOW Transform { + translation 24 0 -30 + children [ + Window { + translation -0.4 0 0 + name "window(7)" + } + Window { + translation 0.4 0 0 + name "window(8)" + } + ] +} +DEF DOUBLE_WINDOW Transform { + translation 12 0 -30 + children [ + Window { + translation -0.4 0 0 + name "window(9)" + } + Window { + translation 0.4 0 0 + name "window(10)" + } + ] +} +DEF DOUBLE_WINDOW Transform { + translation -12 0 -30 + children [ + Window { + translation -0.4 0 0 + name "window(11)" + } + Window { + translation 0.4 0 0 + name "window(12)" + } + ] +} +DEF DOUBLE_WINDOW Transform { + translation -24 0 -30 + children [ + Window { + translation -0.4 0 0 + name "window(13)" + } + Window { + translation 0.4 0 0 + name "window(14)" + } + ] +} +DEF EXTERNAL_WALL Wall { + translation 0 0 30 + name "wall(5)" + size 22.4 2.4 0.2 +} +DEF EXTERNAL_WALL Wall { + translation 18 0 30 + name "wall(6)" + size 10.4 2.4 0.2 +} +DEF EXTERNAL_WALL Wall { + translation -18 0 30 + name "wall(7)" + size 10.4 2.4 0.2 +} +DEF EXTERNAL_WALL Wall { + translation -18 0 30 + name "wall(8)" + size 10.4 2.4 0.2 +} +DEF EXTERNAL_WALL Wall { + translation 27.45 0 30 + name "wall(9)" + size 5.3 2.4 0.2 +} +DEF EXTERNAL_WALL Wall { + translation -27.45 0 30 + name "wall(10)" + size 5.3 2.4 0.2 +} +DEF DOUBLE_WINDOW Transform { + translation 24 0 30 + children [ + Window { + translation -0.4 0 0 + name "window(15)" + } + Window { + translation 0.4 0 0 + name "window(16)" + } + ] +} +DEF DOUBLE_WINDOW Transform { + translation 12 0 30 + children [ + Window { + translation -0.4 0 0 + name "window(17)" + } + Window { + translation 0.4 0 0 + name "window(18)" + } + ] +} +DEF DOUBLE_WINDOW Transform { + translation -12 0 30 + children [ + Window { + translation -0.4 0 0 + name "window(19)" + } + Window { + translation 0.4 0 0 + name "window(20)" + } + ] +} +DEF DOUBLE_WINDOW Transform { + translation -24 0 30 + children [ + Window { + translation -0.4 0 0 + name "window(21)" + } + Window { + translation 0.4 0 0 + name "window(22)" + } + ] +} +DEF EXTERNAL_WALL Wall { + translation 30 0 0 + rotation 0 1 0 1.5708 + name "wall(11)" + size 60 2.4 0.2 +} +DEF EXTERNAL_WALL Wall { + translation -30 0 0 + rotation 0 1 0 1.5708 + name "wall(12)" + size 60 2.4 0.2 +} +DEF INTERNAL_WALL Wall { + translation -10.8 0 -11 + rotation 0 1 0 1.5708 + name "wall(13)" + size 8 2.4 0.2 +} +DEF INTERNAL_WALL Wall { + translation -10.8 0 2.6 + rotation 0 1 0 1.5708 + name "wall(14)" + size 8 2.4 0.2 +} +DEF INTERNAL_WINDOW Window { + translation -10.8 0 -6.6 + rotation 0 1 0 4.71239 +} +DEF INTERNAL_WINDOW Window { + translation -10.8 0 -5.8 + rotation 0 1 0 4.71239 + name "window(1)" +} +DEF INTERNAL_WINDOW Window { + translation -10.8 0 -5 + rotation 0 1 0 4.71239 + name "window(2)" +} +DEF INTERNAL_WINDOW Window { + translation -10.8 0 -4.2 + rotation 0 1 0 4.71239 + name "window(3)" +} +DEF INTERNAL_WINDOW Window { + translation -10.8 0 -3.4 + rotation 0 1 0 4.71239 + name "window(4)" +} +DEF INTERNAL_WINDOW Window { + translation -10.8 0 -2.6 + rotation 0 1 0 4.71239 + name "window(5)" +} +DEF INTERNAL_WINDOW Window { + translation -10.8 0 -1.8 + rotation 0 1 0 4.71239 + name "window(6)" +} +DEF INTERNAL_WALL Wall { + translation 0 0 -22.5 + rotation 0 1 0 1.5708 + name "wall(15)" + size 15 2.4 0.2 +} +DEF INTERNAL_WALL Wall { + translation 22.6 0 19.47 + name "wall(16)" + size 15 2.4 0.2 +} +DEF INTERNAL_WALL Wall { + translation -2.4 0 -15 + name "wall(17)" + size 5 2.4 0.2 +} +DEF INTERNAL_WALL Wall { + translation -8.4 0 -15 + name "wall(18)" + size 5 2.4 0.2 +} +WoodenPallet { + translation 27.6528 0.0185916 -3.65572 + rotation -0.033687506300065374 0.9740331821587109 0.22388504186983704 -0.290318 + boundingObject FALSE +} +WoodenPallet { + translation 27.2125 0.0673767 -2.68777 + rotation 0.020931390902476844 0.6223657294978311 -0.7824466599209943 -0.229223 + name "wooden pallet(1)" + boundingObject FALSE +} +WoodenPallet { + translation 26.3174 0.133879 -2.69913 + rotation -0.1916240622215348 0.00039772812914481797 -0.9814683186889186 3.13481 + name "wooden pallet(2)" + boundingObject FALSE +} +WoodenPallet { + translation 27.9624 0.0761916 -2.15888 + rotation 0.22218899360784491 0.8036559768796215 -0.5520589841178152 -0.213837 + name "wooden pallet(3)" + boundingObject FALSE +} +WoodenPallet { + translation 26.2712 -0.000955835 -1.39216 + rotation -0.0011269403472793512 0.9999983081607331 0.0014538504480203778 -0.796222 + name "wooden pallet(4)" + boundingObject FALSE +} +WoodenPallet { + translation 26.7856 0.184057 -2.68349 + rotation -0.0811041397427491 0.9952054876718023 -0.05466402678653282 -1.30147 + name "wooden pallet(5)" + boundingObject FALSE +} +WoodenPallet { + translation 27.4644 0.178751 -1.26542 + rotation -0.19265300355272164 0.009799040180704486 0.9812180180946802 -3.02896 + name "wooden pallet(6)" + boundingObject FALSE +} +WoodenPallet { + translation 28.25 0.0743134 -3.34206 + rotation -0.08280519684425096 0.6244749762009344 0.7766429704017331 -0.241225 + name "wooden pallet(7)" + boundingObject FALSE +} +WoodenPallet { + translation 28.5899 -0.00135008 -1.37535 + rotation 0.0030836204861510977 0.9999801576528153 -0.005493230866040496 -1.72285 + name "wooden pallet(8)" + boundingObject FALSE +} +WoodenPallet { + translation 27.3443 0.259966 -1.90958 + rotation 0.9423073049594337 0.13130704249497072 0.3079210996526756 0.235868 + name "wooden pallet(9)" + boundingObject FALSE +} +WoodenPallet { + translation 26.3837 0.286405 -2.93448 + rotation -0.34667916342083643 0.08169373850955143 -0.9344194404752943 -0.124508 + name "wooden pallet(10)" + boundingObject FALSE +} +WoodenPallet { + translation 27.8321 0.439539 -2.08579 + rotation -0.032235796364420664 0.9494778929171108 0.31217396479276627 -1.13772 + name "wooden pallet(11)" + boundingObject FALSE +} +WoodenPallet { + translation 26.7651 0.380115 -2.04501 + rotation -0.8247017295217935 0.42981685903255806 -0.3675928794402155 -0.280561 + name "wooden pallet(12)" + boundingObject FALSE +} +WoodenPallet { + translation 26.6264 0.112547 -0.687536 + rotation 0.9990000756434045 0.01503640113854303 -0.04210410318808555 0.185807 + name "wooden pallet(13)" + boundingObject FALSE +} +TrafficCone { + translation 29.2378 -1.77636e-14 -4.67722 +} +TrafficCone { + translation 27.6275 -1.77636e-14 -5.1122 + name "traffic cone(1)" +} +TrafficCone { + translation 26.3918 -1.06581e-14 -4.90082 + name "traffic cone(2)" +} +TrafficCone { + translation 25.2459 -2.13163e-14 -4.05644 + name "traffic cone(3)" +} +TrafficCone { + translation 24.8748 -1.42109e-14 -2.45977 + name "traffic cone(4)" +} +TrafficCone { + translation -27.5033 9.23706e-13 -14.0206 + name "traffic cone(5)" +} +TrafficCone { + translation -22.831 9.166e-13 -13.9376 + name "traffic cone(6)" +} +TrafficCone { + translation -18.9491 4.47642e-13 -14.1135 + rotation 0 1 0 4.71239 + name "traffic cone(7)" +} +TrafficCone { + translation -13.7591 -1.42109e-14 -13.8483 + rotation 0 1 0 4.45059 + name "traffic cone(8)" +} +TrafficCone { + translation 24.7752 -1.42109e-14 -0.88784 + name "traffic cone(9)" +} +TrafficCone { + translation 25.5851 -1.42109e-14 0.255223 + name "traffic cone(10)" +} +TrafficCone { + translation 26.7417 -1.42109e-14 0.835499 + name "traffic cone(11)" +} +TrafficCone { + translation 27.9622 -1.42109e-14 0.742603 + name "traffic cone(12)" +} +TrafficCone { + translation 29.324 -1.42109e-14 0.282551 + name "traffic cone(13)" +} +Door { + translation -5.4 0 -15 +} +DEF KITCHEN Transform { + translation 27.8 0 21.2 + rotation 0 1 0 4.71239 + children [ + Cabinet { + translation 1 0.83 -2.15 + depth 0.7 + outerThickness 0.02 + rowsHeights [ + 0.2, 0.2, 0.2, 0.2, 0.2, 0.34 + ] + columnsWidths [ + 0.4 + ] + layout [ + "LeftSidedDoor (1, 1, 1, 6, 1.5)" + "Shelf (1,2, 1, 0)" + "Shelf (1,3, 1, 0)" + "Shelf (1,4, 1, 0)" + "Shelf (1,5, 1, 0)" + "Shelf (1,6, 1, 0)" + ] + handle CabinetHandle { + translation -0.3 0 0 + handleLength 0.1 + handleRadius 0.008 + handleColor 0.427451 0.513725 0.533333 + } + } + Cabinet { + translation -1.65 0.15 0.11 + rotation 0 1 0 1.5708 + name "cabinet(1)" + depth 0.67 + outerThickness 0.02 + rowsHeights [ + 0.68, 0.25, 0.25, 0.25, 0.25, 0.34 + ] + columnsWidths [ + 0.44 + ] + layout [ + "RightSidedDoor (1, 2, 1, 3, 1.5)" + "RightSidedDoor (1, 5, 1, 2, 1.5)" + "Shelf (1,2, 1, 0)" + "Shelf (1,3, 1, 0)" + "Shelf (1,4, 1, 0)" + "Shelf (1,5, 1, 0)" + "Shelf (1,6, 1, 0)" + ] + handle CabinetHandle { + translation -0.15 0 0 + handleLength 0.1 + handleRadius 0.008 + handleColor 0.427451 0.513725 0.533333 + } + } + Cabinet { + translation 0.1 1.4 -2.15 + name "cabinet(2)" + outerThickness 0.02 + rowsHeights [ + 0.21, 0.21, 0.22 + ] + columnsWidths [ + 0.44, 0.44, 0.44 + ] + layout [ + "RightSidedDoor (1, 1, 1, 3, 1.5)" + "LeftSidedDoor (2, 1, 1, 3, 1.5)" + "LeftSidedDoor (3, 1, 1, 3, 1.5)" + "Shelf (1, 2, 3, 0)" + "Shelf (1, 3, 2, 0)" + "Shelf (1, 1, 0, 1)" + "Shelf (2, 1, 0, 3)" + ] + handle CabinetHandle { + translation -0.2 0 0 + handleLength 0.1 + handleRadius 0.008 + handleColor 0.427451 0.513725 0.533333 + } + } + Cabinet { + translation -1.647 1.4 -0.37 + rotation 0 1 0 1.5708 + name "cabinet(3)" + outerThickness 0.02 + rowsHeights [ + 0.21, 0.21, 0.22 + ] + columnsWidths [ + 0.44 + ] + layout [ + "RightSidedDoor (1, 1, 1, 3, 1.5)" + "Shelf (1, 2 ,1 , 0)" + "Shelf (1, 3 ,1 , 0)" + ] + handle CabinetHandle { + translation -0.2 0 0 + handleLength 0.1 + handleRadius 0.008 + handleColor 0.427451 0.513725 0.533333 + } + } + Cabinet { + translation -1.48 0.15 -0.79 + rotation 0 1 0 1.5708 + name "cabinet(4)" + outerThickness 0.02 + rowsHeights [ + 0.21, 0.21, 0.22 + ] + columnsWidths [ + 0.34, 0.47, 0.47 + ] + layout [ + "RightSidedDoor (2, 1, 1, 3, 1.5)" + "LeftSidedDoor (3, 1, 1, 3, 1.5)" + "RightSidedDoor (1, 1, 1, 3, 1.5)" + "Shelf (1, 2, 1, 0)" + "Shelf (1, 3, 1, 0)" + "Shelf (1, 1, 0, 3)" + "Shelf (2, 1, 0, 3)" + ] + handle CabinetHandle { + translation 0.1 0 0 + handleLength 0.1 + handleRadius 0.008 + handleColor 0.427451 0.513725 0.533333 + } + } + Cabinet { + translation 0.12 0.15 -2.15 + name "cabinet(5)" + depth 0.7 + outerThickness 0.02 + rowsHeights [ + 0.25, 0.25, 0.14 + ] + columnsWidths [ + 0.76, 0.54, 0.43, 0.43 + ] + layout [ + "LeftSidedDoor (2, 1, 1, 2, 1.5)" + "LeftSidedDoor (4, 1, 1, 3, 1.5)" + "RightSidedDoor (3, 1, 1, 3, 1.5)" + "Drawer (1, 1, 1, 1, 3.5)" + "Drawer (1, 2, 1, 1, 3.5)" + "Drawer (1, 3, 1, 1, 3.5)" + "Drawer (2, 3, 1, 1, 3.5)" + "Shelf (1, 2, 1, 0)" + "Shelf (1, 3, 2, 0)" + "Shelf (3, 2, 2, 0)" + "Shelf (1, 1, 0, 3)" + "Shelf (2, 1, 0, 3)" + "Shelf (3, 1, 0, 1)" + ] + handle CabinetHandle { + handleLength 0.1 + handleRadius 0.008 + handleColor 0.427451 0.513725 0.533333 + } + } + SolidBox { + translation 0.12 0.07 -1.55 + size 2.2 0.16 0.2 + appearance PBRAppearance { + baseColor 0.8 0.8 0.8 + roughness 0.5 + metalness 0 + textureTransform TextureTransform { + scale 4 4 + } + } + } + SolidBox { + translation -1.08 0.07 -0.65 + rotation 0 1 0 1.5708 + name "box(1)" + size 2 0.16 0.2 + appearance PBRAppearance { + baseColor 0.8 0.8 0.8 + roughness 0.5 + metalness 0 + textureTransform TextureTransform { + scale 4 4 + } + } + } + SolidBox { + translation 1.12 0.07 -1.9 + rotation 0 -1 0 4.71239 + name "box(2)" + size 0.5 0.16 0.2 + appearance PBRAppearance { + roughness 0.5 + metalness 0 + textureTransform TextureTransform { + scale 4 4 + } + } + } + SolidBox { + translation -1.415 0.07 0.25 + rotation 0 -1 0 6.28318 + name "box(3)" + size 0.47 0.16 0.2 + appearance PBRAppearance { + baseColor 0.8 0.8 0.8 + roughness 0.5 + metalness 0 + textureTransform TextureTransform { + scale 4 4 + } + } + } + Fridge { + translation 1.57 0 -1.8 + rotation 0 1 0 4.71239 + } + Worktop { + translation -1.31 0.86 -0.345 + rotation 0 1 0 4.71239 + size 0.43 0.06 0.7 + } + Worktop { + translation -1.531 0.86 -0.78 + rotation 0 1 0 4.71239 + name "worktop(1)" + size 0.44 0.06 0.237 + } + Worktop { + translation -1.003 0.86 -0.780001 + rotation 0 1 0 4.71239 + name "worktop(2)" + size 0.442 0.06 0.085 + } + Worktop { + translation -1.306 0.86 -1.22 + rotation 0 -1 0 1.5708 + name "worktop(3)" + size 0.44 0.06 0.69 + } + Worktop { + translation -0.435 0.86 -1.79 + name "worktop(4)" + size 2.43 0.06 0.7 + } + Sink { + translation -1.33 0.87 -0.78 + rotation 0 1 0 4.71239 + } + HotPlate { + translation -1.14971 0.86 -1.62912 + rotation 0 -1 0 5.49779 + } + Oven { + translation -1.24 0.51 0.11 + } + ] +} +DEF PIONEER_3AT Pioneer3at { + translation 1.69482 0.11 4.10279 + controller "ros" + controllerArgs [ + "--name=pioneer3at" + ] + extensionSlot [ + Camera { + translation 0 0.17 -0.22 + width 256 + height 128 + motionBlur 500 + noise 0.02 + } + Accelerometer { + lookupTable [ + -39.24 -39.24 0.005 + 39.24 39.24 0.005 + ] + } + Gyro { + lookupTable [ + -50 -50 0.005 + 50 50 0.005 + ] + } + SickLms291 { + translation 0 0.23 -0.136 + noise 0.1 + } + GPS { + } + InertialUnit { + } + ] +} +Table { + translation 22.5 0 21.6 + size 4.2 0.74 1 +} +Chair { + translation 23.2032 0 22.0662 + rotation 0 -1 0 4.71239 +} +Chair { + translation 23.2032 0 21.2162 + rotation 0 1 0 4.71239 + name "chair(1)" +} +Chair { + translation 22.4132 0 22.0562 + rotation 0 -1 0 4.71239 + name "chair(2)" +} +Chair { + translation 22.4132 0 21.2162 + rotation 0 1 0 4.71239 + name "chair(3)" +} +Chair { + translation 21.6732 0 22.0662 + rotation 0 -1 0 4.71239 + name "chair(4)" +} +Chair { + translation 21.6732 0 21.2162 + rotation 0 1 0 4.71239 + name "chair(5)" +} +Chair { + translation 20.9632 0 22.0662 + rotation 0 -1 0 4.71239 + name "chair(6)" +} +Chair { + translation 20.9632 0 21.2162 + rotation 0 1 0 4.71239 + name "chair(7)" +} +Chair { + translation 23.9732 0 22.0662 + rotation 0 -1 0 4.71239 + name "chair(8)" +} +Chair { + translation 23.9732 0 21.2162 + rotation 0 1 0 4.71239 + name "chair(9)" +} +DEF TREE Solid { + translation 21.2655 1.06048e-12 -13.0987 + rotation 0 1 0 0.785398 + scale 1.7 1.7 1.7 + children [ + PottedTree { + rotation 0 1 0 0.261799 + } + ] +} +DEF TREE Solid { + translation -21.2183 1.06137e-12 21.6362 + rotation 0 -1 0 3.66519 + scale 1.7 1.7 1.7 + children [ + PottedTree { + } + ] + name "solid(1)" +} +DEF TREE Solid { + translation -21.1851 1.06137e-12 20.2765 + rotation 0 -1 0 6.02139 + scale 1.7 1.7 1.7 + children [ + PottedTree { + } + ] + name "solid(2)" +} +DEF TREE Solid { + translation -21.223 1.06137e-12 14.4309 + rotation 0 -1 0 6.02139 + scale 1.7 1.7 1.7 + children [ + PottedTree { + } + ] + name "solid(3)" +} +DEF TREE Solid { + translation -21.1983 1.06137e-12 13.1633 + rotation 0 1 0 0.785398 + scale 1.7 1.7 1.7 + children [ + PottedTree { + } + ] + name "solid(4)" +} +DEF TREE Solid { + translation -9.98679 1.0667e-12 5.37678 + rotation 0 1 0 0.785398 + scale 1.7 1.7 1.7 + children [ + PottedTree { + } + ] + name "solid(5)" +} +DEF TREE Solid { + translation -10.1726 1.0667e-12 -0.216214 + rotation 0 1 0 0.785398 + scale 1.7 1.7 1.7 + children [ + PottedTree { + } + ] + name "solid(6)" +} +DEF TREE Solid { + translation -10.067 1.0667e-12 -8.47773 + rotation 0 1 0 0.785398 + scale 1.7 1.7 1.7 + children [ + PottedTree { + } + ] + name "solid(7)" +} +DEF TREE Solid { + translation -9.86925 1.0667e-12 -13.5549 + rotation 0 1 0 0.785398 + scale 1.7 1.7 1.7 + children [ + PottedTree { + } + ] + name "solid(8)" +} +DEF TREE Solid { + translation 1.30651 1.05959e-12 -28.489 + rotation 0 1 0 0.785398 + scale 1.7 1.7 1.7 + children [ + PottedTree { + } + ] + name "solid(9)" +} +DEF TREE Solid { + translation 21.2939 1.05071e-12 -14.4648 + rotation 0 1 0 0.785398 + scale 1.7 1.7 1.7 + children [ + PottedTree { + } + ] + name "solid(10)" +} +DEF TREE Solid { + translation 21.263 1.0516e-12 -20.4389 + rotation 0 1 0 0.785398 + scale 1.7 1.7 1.7 + children [ + PottedTree { + } + ] + name "solid(11)" +} +DEF TREE Solid { + translation 21.2686 1.0516e-12 -21.92 + scale 1.7 1.7 1.7 + children [ + PottedTree { + } + ] + name "solid(12)" +} +PottedTree { + translation 18.8987 3.55271e-15 29.4672 +} +PottedTree { + translation 27.5526 3.55271e-15 26.7018 + name "potted tree(1)" +} +PottedTree { + translation 17.1715 3.55271e-15 20.9225 + name "potted tree(2)" +} +Sofa { + translation 27.9791 0 28.4787 + rotation 0 1 0 2.35619 +} +DEF OFFICES Transform { + children [ + Panel { + translation 28.4604 0 -24.5373 + } + Panel { + translation 28.4604 0 -17.2973 + name "panel(1)" + } + Panel { + translation 28.4604 0 -10.2573 + name "panel(2)" + } + Panel { + translation 27.0304 0 -24.5573 + name "panel(3)" + } + Panel { + translation 27.0304 0 -17.2873 + name "panel(4)" + } + Panel { + translation 27.0304 0 -10.2573 + name "panel(5)" + } + Panel { + translation 27.0774 0 -10.6551 + rotation 0 1 0 1.5708 + name "panel(6)" + } + Panel { + translation 27.0774 0 -15.6551 + rotation 0 1 0 1.5708 + name "panel(7)" + } + Panel { + translation 27.0774 0 -17.7651 + rotation 0 1 0 1.5708 + name "panel(8)" + } + Panel { + translation 27.0774 0 -22.8751 + rotation 0 1 0 1.5708 + name "panel(9)" + } + Panel { + translation 27.0774 0 -24.9451 + rotation 0 1 0 1.5708 + name "panel(10)" + } + Panel { + translation 24.2974 0 -10.6551 + rotation 0 1 0 1.5708 + name "panel(11)" + } + Panel { + translation 24.2974 0 -15.6951 + rotation 0 1 0 1.5708 + name "panel(12)" + } + Panel { + translation 24.2974 0 -17.8051 + rotation 0 1 0 1.5708 + name "panel(13)" + } + Panel { + translation 24.2974 0 -22.8551 + rotation 0 1 0 1.5708 + name "panel(14)" + } + Panel { + translation 24.2974 0 -25.0151 + rotation 0 1 0 1.5708 + name "panel(15)" + } + Panel { + translation 21.2474 0 -10.6551 + rotation 0 1 0 1.5708 + name "panel(16)" + } + Panel { + translation 21.2474 0 -15.6951 + rotation 0 1 0 1.5708 + name "panel(17)" + } + Panel { + translation 21.2474 0 -17.7551 + rotation 0 1 0 1.5708 + name "panel(18)" + } + Panel { + translation 21.2474 0 -24.9351 + rotation 0 1 0 1.5708 + name "panel(19)" + } + Panel { + translation 21.2474 0 -28.4451 + rotation 0 1 0 1.5708 + name "panel(20)" + } + Panel { + translation 21.2474 0 -26.8251 + rotation 0 1 0 1.5708 + name "panel(21)" + } + Panel { + translation 21.2474 0 -22.8651 + rotation 0 1 0 1.5708 + name "panel(22)" + } + Panel { + translation 25.5604 0 -24.5873 + name "panel(23)" + } + Panel { + translation 25.5604 0 -17.3073 + name "panel(24)" + } + Panel { + translation 25.5604 0 -10.2573 + name "panel(25)" + } + Panel { + translation 24.1004 0 -24.5973 + name "panel(26)" + } + Panel { + translation 24.1004 0 -17.3373 + name "panel(27)" + } + Panel { + translation 24.1004 0 -10.2573 + name "panel(28)" + } + Panel { + translation 22.5504 0 -24.5873 + name "panel(29)" + } + Panel { + translation 22.5504 0 -17.3273 + name "panel(30)" + } + Panel { + translation 22.5504 0 -10.2573 + name "panel(31)" + } + Panel { + translation 20.9704 0 -10.2573 + name "panel(32)" + } + Panel { + translation 20.9704 0 -24.5773 + name "panel(33)" + } + Panel { + translation 20.9704 0 -17.3573 + name "panel(34)" + } + WoodenChair { + translation 28.2877 7.10543e-15 -16.5637 + } + WoodenChair { + translation 28.2877 7.10543e-15 -23.9137 + name "wooden chair(1)" + } + WoodenChair { + translation 28.2877 7.10543e-15 -18.1537 + rotation 0 1 0 3.14159 + name "wooden chair(2)" + } + WoodenChair { + translation 28.2877 7.10543e-15 -25.1237 + rotation 0 1 0 3.14159 + name "wooden chair(3)" + } + WoodenChair { + translation 25.7177 7.10543e-15 -23.8937 + name "wooden chair(4)" + } + WoodenChair { + translation 25.7177 7.10543e-15 -18.0837 + rotation 0 1 0 3.14159 + name "wooden chair(5)" + } + WoodenChair { + translation 28.2877 7.10543e-15 -11.1637 + rotation 0 1 0 3.14159 + name "wooden chair(6)" + } + WoodenChair { + translation 25.7177 7.10543e-15 -25.2037 + rotation 0 1 0 3.14159 + name "wooden chair(7)" + } + WoodenChair { + translation 22.9577 7.10543e-15 -23.8537 + name "wooden chair(8)" + } + WoodenChair { + translation 25.7177 7.10543e-15 -16.5637 + name "wooden chair(9)" + } + WoodenChair { + translation 22.9577 7.10543e-15 -18.0537 + rotation 0 1 0 3.14159 + name "wooden chair(10)" + } + WoodenChair { + translation 25.7177 7.10543e-15 -11.1037 + rotation 0 1 0 3.14159 + name "wooden chair(11)" + } + WoodenChair { + translation 22.9577 7.10543e-15 -25.0837 + rotation 0 1 0 3.14159 + name "wooden chair(12)" + } + WoodenChair { + translation 22.9577 7.10543e-15 -16.5637 + name "wooden chair(13)" + } + WoodenChair { + translation 22.9577 7.10543e-15 -11.1937 + rotation 0 1 0 3.14159 + name "wooden chair(14)" + } + Desk { + translation 28.2877 7.10543e-15 -16.1837 + rotation 0 1 0 6.28319 + } + Desk { + translation 28.2877 7.10543e-15 -25.5337 + rotation 0 1 0 6.28319 + name "desk(1)" + } + Desk { + translation 28.2877 7.10543e-15 -11.5037 + rotation 0 1 0 6.28319 + name "desk(2)" + } + Desk { + translation 28.2877 7.10543e-15 -23.5237 + rotation 0 1 0 6.28319 + name "desk(3)" + } + Desk { + translation 25.6977 7.10543e-15 -16.1837 + rotation 0 1 0 6.28319 + name "desk(4)" + } + Desk { + translation 25.6977 7.10543e-15 -18.4537 + rotation 0 1 0 6.28319 + name "desk(5)" + } + Desk { + translation 25.6977 7.10543e-15 -11.5337 + rotation 0 1 0 6.28319 + name "desk(6)" + } + Desk { + translation 22.9277 7.10543e-15 -16.1837 + rotation 0 1 0 6.28319 + name "desk(7)" + } + Desk { + translation 22.9277 7.10543e-15 -11.5737 + rotation 0 1 0 6.28319 + name "desk(8)" + } + Desk { + translation 25.6977 7.10543e-15 -25.5537 + rotation 0 1 0 6.28319 + name "desk(9)" + } + Desk { + translation 28.2877 7.10543e-15 -18.5337 + rotation 0 1 0 6.28319 + name "desk(10)" + } + Desk { + translation 22.9277 7.10543e-15 -18.4537 + rotation 0 1 0 6.28319 + name "desk(11)" + } + Desk { + translation 25.6977 7.10543e-15 -23.4937 + rotation 0 1 0 6.28319 + name "desk(12)" + } + Desk { + translation 22.9277 7.10543e-15 -23.5337 + rotation 0 1 0 6.28319 + name "desk(13)" + } + Desk { + translation 22.9277 7.10543e-15 -25.4837 + rotation 0 1 0 6.28319 + name "desk(14)" + } + ] +} +DEF OFFICES Transform { + rotation 0 1 0 3.14159 + children [ + Panel { + translation 28.4604 0 -24.5373 + name "panel(35)" + } + Panel { + translation 28.4604 0 -17.2973 + name "panel(36)" + } + Panel { + translation 28.4604 0 -10.2573 + name "panel(37)" + } + Panel { + translation 27.0304 0 -24.5573 + name "panel(38)" + } + Panel { + translation 27.0304 0 -17.2873 + name "panel(39)" + } + Panel { + translation 27.0304 0 -10.2573 + name "panel(40)" + } + Panel { + translation 27.0774 0 -10.6551 + rotation 0 1 0 1.5708 + name "panel(41)" + } + Panel { + translation 27.0774 0 -15.6551 + rotation 0 1 0 1.5708 + name "panel(42)" + } + Panel { + translation 27.0774 0 -17.7651 + rotation 0 1 0 1.5708 + name "panel(43)" + } + Panel { + translation 27.0774 0 -22.8751 + rotation 0 1 0 1.5708 + name "panel(44)" + } + Panel { + translation 27.0774 0 -24.9451 + rotation 0 1 0 1.5708 + name "panel(45)" + } + Panel { + translation 24.2974 0 -10.6551 + rotation 0 1 0 1.5708 + name "panel(46)" + } + Panel { + translation 24.2974 0 -15.6951 + rotation 0 1 0 1.5708 + name "panel(47)" + } + Panel { + translation 24.2974 0 -17.8051 + rotation 0 1 0 1.5708 + name "panel(48)" + } + Panel { + translation 24.2974 0 -22.8551 + rotation 0 1 0 1.5708 + name "panel(49)" + } + Panel { + translation 24.2974 0 -25.0151 + rotation 0 1 0 1.5708 + name "panel(50)" + } + Panel { + translation 21.2474 0 -10.6551 + rotation 0 1 0 1.5708 + name "panel(51)" + } + Panel { + translation 21.2474 0 -15.6951 + rotation 0 1 0 1.5708 + name "panel(52)" + } + Panel { + translation 21.2474 0 -17.7551 + rotation 0 1 0 1.5708 + name "panel(53)" + } + Panel { + translation 21.2474 0 -22.8651 + rotation 0 1 0 1.5708 + name "panel(54)" + } + Panel { + translation 21.2474 0 -24.8851 + rotation 0 1 0 1.5708 + name "panel(55)" + } + Panel { + translation 21.2474 0 -26.6151 + rotation 0 1 0 1.5708 + name "panel(56)" + } + Panel { + translation 21.2474 0 -28.2551 + rotation 0 1 0 1.5708 + name "panel(57)" + } + Panel { + translation 25.5604 0 -24.5873 + name "panel(58)" + } + Panel { + translation 25.5604 0 -17.3073 + name "panel(59)" + } + Panel { + translation 25.5604 0 -10.2573 + name "panel(60)" + } + Panel { + translation 24.1004 0 -24.5973 + name "panel(61)" + } + Panel { + translation 24.1004 0 -17.3373 + name "panel(62)" + } + Panel { + translation 24.1004 0 -10.2573 + name "panel(63)" + } + Panel { + translation 22.5504 0 -24.5873 + name "panel(64)" + } + Panel { + translation 22.5504 0 -17.3273 + name "panel(65)" + } + Panel { + translation 22.5504 0 -10.2573 + name "panel(66)" + } + Panel { + translation 20.9704 0 -10.2573 + name "panel(67)" + } + Panel { + translation 20.9704 0 -24.5773 + name "panel(68)" + } + Panel { + translation 20.9704 0 -17.3573 + name "panel(69)" + } + WoodenChair { + translation 28.2877 7.10543e-15 -16.5637 + name "wooden chair(15)" + } + WoodenChair { + translation 28.2877 7.10543e-15 -23.9137 + name "wooden chair(16)" + } + WoodenChair { + translation 28.2877 7.10543e-15 -18.1537 + rotation 0 1 0 3.14159 + name "wooden chair(17)" + } + WoodenChair { + translation 28.2877 7.10543e-15 -25.1237 + rotation 0 1 0 3.14159 + name "wooden chair(18)" + } + WoodenChair { + translation 25.7177 7.10543e-15 -23.8937 + name "wooden chair(19)" + } + WoodenChair { + translation 25.7177 7.10543e-15 -18.0837 + rotation 0 1 0 3.14159 + name "wooden chair(20)" + } + WoodenChair { + translation 28.2877 7.10543e-15 -11.1637 + rotation 0 1 0 3.14159 + name "wooden chair(21)" + } + WoodenChair { + translation 25.7177 7.10543e-15 -25.2037 + rotation 0 1 0 3.14159 + name "wooden chair(22)" + } + WoodenChair { + translation 22.9577 7.10543e-15 -23.8537 + name "wooden chair(23)" + } + WoodenChair { + translation 25.7177 7.10543e-15 -16.5637 + name "wooden chair(24)" + } + WoodenChair { + translation 22.9577 7.10543e-15 -18.0537 + rotation 0 1 0 3.14159 + name "wooden chair(25)" + } + WoodenChair { + translation 25.7177 7.10543e-15 -11.1037 + rotation 0 1 0 3.14159 + name "wooden chair(26)" + } + WoodenChair { + translation 22.9577 7.10543e-15 -25.0837 + rotation 0 1 0 3.14159 + name "wooden chair(27)" + } + WoodenChair { + translation 22.9577 7.10543e-15 -16.5637 + name "wooden chair(28)" + } + WoodenChair { + translation 22.9577 7.10543e-15 -11.1937 + rotation 0 1 0 3.14159 + name "wooden chair(29)" + } + Desk { + translation 28.2877 7.10543e-15 -16.1837 + rotation 0 1 0 6.28319 + name "desk(15)" + } + Desk { + translation 28.2877 7.10543e-15 -25.5337 + rotation 0 1 0 6.28319 + name "desk(16)" + } + Desk { + translation 28.2877 7.10543e-15 -11.5037 + rotation 0 1 0 6.28319 + name "desk(17)" + } + Desk { + translation 28.2877 7.10543e-15 -23.5237 + rotation 0 1 0 6.28319 + name "desk(18)" + } + Desk { + translation 25.6977 7.10543e-15 -16.1837 + rotation 0 1 0 6.28319 + name "desk(19)" + } + Desk { + translation 25.6977 7.10543e-15 -18.4537 + rotation 0 1 0 6.28319 + name "desk(20)" + } + Desk { + translation 25.6977 7.10543e-15 -11.5337 + rotation 0 1 0 6.28319 + name "desk(21)" + } + Desk { + translation 22.9277 7.10543e-15 -16.1837 + rotation 0 1 0 6.28319 + name "desk(22)" + } + Desk { + translation 22.9277 7.10543e-15 -11.5737 + rotation 0 1 0 6.28319 + name "desk(23)" + } + Desk { + translation 25.6977 7.10543e-15 -25.5537 + rotation 0 1 0 6.28319 + name "desk(24)" + } + Desk { + translation 28.2877 7.10543e-15 -18.5337 + rotation 0 1 0 6.28319 + name "desk(25)" + } + Desk { + translation 22.9277 7.10543e-15 -18.4537 + rotation 0 1 0 6.28319 + name "desk(26)" + } + Desk { + translation 25.6977 7.10543e-15 -23.4937 + rotation 0 1 0 6.28319 + name "desk(27)" + } + Desk { + translation 22.9277 7.10543e-15 -23.5337 + rotation 0 1 0 6.28319 + name "desk(28)" + } + Desk { + translation 22.9277 7.10543e-15 -25.4837 + rotation 0 1 0 6.28319 + name "desk(29)" + } + ] +} +DEF BOXES Transform { + children [ + WoodenBox { + translation 26.7873 0.89 9.13591 + } + WoodenBox { + translation 25.3406 0.3 9.13625 + name "wooden box(1)" + } + WoodenBox { + translation 25.8306 0.91 9.13625 + name "wooden box(2)" + } + WoodenBox { + translation 24.8506 0.9 9.13625 + name "wooden box(3)" + } + WoodenBox { + translation 24.3706 0.3 9.13625 + name "wooden box(4)" + } + WoodenBox { + translation 26.3006 0.3 9.13625 + name "wooden box(5)" + } + WoodenBox { + translation 27.317 0.3 9.14677 + name "wooden box(6)" + } + ] +} +DEF BOXES Transform { + translation -7 0 0 + children [ + WoodenBox { + translation 26.7873 0.89 9.13591 + name "wooden box(7)" + } + WoodenBox { + translation 25.3406 0.3 9.13625 + name "wooden box(8)" + } + WoodenBox { + translation 25.8306 0.91 9.13625 + name "wooden box(9)" + } + WoodenBox { + translation 24.8506 0.9 9.13625 + name "wooden box(10)" + } + WoodenBox { + translation 24.3706 0.3 9.13625 + name "wooden box(11)" + } + WoodenBox { + translation 26.3006 0.3 9.13625 + name "wooden box(12)" + } + WoodenBox { + translation 27.317 0.3 9.14677 + name "wooden box(13)" + } + ] +} +DEF BOXES Transform { + translation 0 0 3 + children [ + WoodenBox { + translation 26.7873 0.89 9.13591 + name "wooden box(14)" + } + WoodenBox { + translation 25.3406 0.3 9.13625 + name "wooden box(15)" + } + WoodenBox { + translation 25.8306 0.91 9.13625 + name "wooden box(16)" + } + WoodenBox { + translation 24.8506 0.9 9.13625 + name "wooden box(17)" + } + WoodenBox { + translation 24.3706 0.3 9.13625 + name "wooden box(18)" + } + WoodenBox { + translation 26.3006 0.3 9.13625 + name "wooden box(19)" + } + WoodenBox { + translation 27.317 0.3 9.14677 + name "wooden box(20)" + } + ] +} +DEF BOXES Transform { + translation -7 0 3 + children [ + WoodenBox { + translation 26.7873 0.89 9.13591 + name "wooden box(21)" + } + WoodenBox { + translation 25.3406 0.3 9.13625 + name "wooden box(22)" + } + WoodenBox { + translation 25.8306 0.91 9.13625 + name "wooden box(23)" + } + WoodenBox { + translation 24.8506 0.9 9.13625 + name "wooden box(24)" + } + WoodenBox { + translation 24.3706 0.3 9.13625 + name "wooden box(25)" + } + WoodenBox { + translation 26.3006 0.3 9.13625 + name "wooden box(26)" + } + WoodenBox { + translation 27.317 0.3 9.14677 + name "wooden box(27)" + } + ] +} +DEF BOXES Transform { + translation 0 0 6 + children [ + WoodenBox { + translation 26.7873 0.89 9.13591 + name "wooden box(28)" + } + WoodenBox { + translation 25.3406 0.3 9.13625 + name "wooden box(29)" + } + WoodenBox { + translation 25.8306 0.91 9.13625 + name "wooden box(30)" + } + WoodenBox { + translation 24.8506 0.9 9.13625 + name "wooden box(31)" + } + WoodenBox { + translation 24.3706 0.3 9.13625 + name "wooden box(32)" + } + WoodenBox { + translation 26.3006 0.3 9.13625 + name "wooden box(33)" + } + WoodenBox { + translation 27.317 0.3 9.14677 + name "wooden box(34)" + } + ] +} +StraightStairs { + translation -29.2069 7.10543e-15 -8.43695 + rotation 9.58976e-09 -1 -9.58979e-09 4.71239 + stepRise 0.2 + nSteps 11 + stepAppearance PBRAppearance { + roughness 0.5 + metalness 0 + textureTransform TextureTransform { + scale 1 2 + } + } + stringerAppearance PBRAppearance { + roughness 0.5 + metalness 0 + textureTransform TextureTransform { + rotation 1.1 + } + } + leftRail [] + rightRail [ + StraightStairsRail { + run 4.4 + rise 2.2 + newelHeight 0.98 + balusterHeight 0.7 + balusterRadius 0.02 + nBalusters 15 + appearance PBRAppearance { + roughness 0.5 + metalness 0 + textureTransform TextureTransform { + rotation 1.5708 + } + } + } + ] +} +StraightStairs { + translation -0.529031 7.10543e-15 29.2481 + rotation 0 -1 0 3.14159 + name "straight stairs(1)" + stepRise 0.2 + nSteps 11 + stepAppearance PBRAppearance { + roughness 0.5 + metalness 0 + textureTransform TextureTransform { + scale 1 2 + } + } + stringerAppearance PBRAppearance { + roughness 0.5 + metalness 0 + textureTransform TextureTransform { + rotation 1.1 + } + } + leftRail [] + rightRail [ + StraightStairsRail { + run 4.4 + rise 2.2 + newelHeight 0.98 + balusterHeight 0.7 + balusterRadius 0.02 + nBalusters 15 + appearance PBRAppearance { + roughness 0.5 + metalness 0 + textureTransform TextureTransform { + rotation 1.5708 + } + } + } + ] +} +StraightStairs { + translation 0.76 0 -19 + rotation 0 1 0 1.5708 + name "straight stairs(2)" + stepRise 0.2 + nSteps 11 + stepAppearance PBRAppearance { + roughness 0.5 + metalness 0 + textureTransform TextureTransform { + scale 1 2 + } + } + stringerAppearance PBRAppearance { + roughness 0.5 + metalness 0 + textureTransform TextureTransform { + rotation 1.1 + } + } + leftRail [] + rightRail [ + StraightStairsRail { + run 4.4 + rise 2.2 + newelHeight 0.98 + balusterHeight 0.7 + balusterRadius 0.02 + nBalusters 15 + appearance PBRAppearance { + roughness 0.5 + metalness 0 + textureTransform TextureTransform { + rotation 1.5708 + } + } + } + ] +} +DEF BOXES Transform { + translation -7 0 6 + children [ + WoodenBox { + translation 26.7873 0.89 9.13591 + name "wooden box(35)" + } + WoodenBox { + translation 25.3406 0.3 9.13625 + name "wooden box(36)" + } + WoodenBox { + translation 25.8306 0.91 9.13625 + name "wooden box(37)" + } + WoodenBox { + translation 24.8506 0.9 9.13625 + name "wooden box(38)" + } + WoodenBox { + translation 24.3706 0.3 9.13625 + name "wooden box(39)" + } + WoodenBox { + translation 26.3006 0.3 9.13625 + name "wooden box(40)" + } + WoodenBox { + translation 27.317 0.3 9.14677 + name "wooden box(41)" + } + ] +} +OilBarrel { + translation -9.26761 0.44 -20.0914 +} +OilBarrel { + translation -26.1118 0.44 -19.0086 + name "oil barrel(1)" +} +OilBarrel { + translation -21.9075 0 -18.9476 + name "oil barrel(2)" +} +OilBarrel { + translation -27.6392 0.44 -26.4716 + name "oil barrel(3)" +} +OilBarrel { + translation -25.5943 0.44 -22.115 + name "oil barrel(4)" +} +OilBarrel { + translation -23.236 0.44 -26.5773 + name "oil barrel(5)" +} +OilBarrel { + translation -18.3049 0.44 -20.8934 + name "oil barrel(6)" +} +OilBarrel { + translation -13.8601 0 -17.7296 + name "oil barrel(7)" +} +OilBarrel { + translation -13.9827 0.44 -23.2832 + name "oil barrel(8)" +} +OilBarrel { + translation -15.759 0.44 -27.9069 + name "oil barrel(9)" +} +OilBarrel { + translation -10.0871 0.44 -26.0751 + name "oil barrel(10)" +} +OilBarrel { + translation -6.54998 0 -22.3303 + name "oil barrel(11)" +} +OilBarrel { + translation -3.05266 0.44 -25.4792 + name "oil barrel(12)" +} +OilBarrel { + translation -2.93961 0.44 -17.7793 + name "oil barrel(13)" +} +PanelWithTubes { + translation 7.47218 1.06581e-14 -3.68619 + rotation 0 1 0 3.14159 +} +PanelWithTubes { + translation 7.47218 1.06581e-14 0.993814 + name "panel with tubes(1)" +} +PanelWithTubes { + translation 9.23218 1.06581e-14 -3.68619 + rotation 0 1 0 3.14159 + name "panel with tubes(2)" +} +PanelWithTubes { + translation 9.23218 1.06581e-14 0.993814 + name "panel with tubes(3)" +} +PanelWithTubes { + translation 6.57218 1.06581e-14 -3.68619 + rotation 0 1 0 3.14159 + name "panel with tubes(4)" +} +PanelWithTubes { + translation 6.57218 1.06581e-14 0.993814 + name "panel with tubes(5)" +} +PanelWithTubes { + translation 5.65218 1.06581e-14 -3.68619 + rotation 0 1 0 3.14159 + name "panel with tubes(6)" +} +PanelWithTubes { + translation 5.65218 1.06581e-14 0.993814 + name "panel with tubes(7)" +} +PanelWithTubes { + translation 5.25302 1.06581e-14 0.48228 + rotation 0 1 0 4.71239 + name "panel with tubes(8)" +} +PanelWithTubes { + translation 9.64302 1.06581e-14 0.48228 + rotation 0 -1 0 4.71239 + name "panel with tubes(9)" +} +PanelWithTubes { + translation 9.64302 1.06581e-14 -0.42772 + rotation 0 -1 0 4.71239 + name "panel with tubes(10)" +} +PanelWithTubes { + translation 5.25302 1.06581e-14 -0.42772 + rotation 0 1 0 4.71239 + name "panel with tubes(11)" +} +PanelWithTubes { + translation 9.64302 1.06581e-14 -1.38772 + rotation 0 -1 0 4.71239 + name "panel with tubes(12)" +} +PanelWithTubes { + translation 5.25302 1.06581e-14 -1.38772 + rotation 0 1 0 4.71239 + name "panel with tubes(13)" +} +PanelWithTubes { + translation 9.64302 1.06581e-14 -2.33772 + rotation 0 -1 0 4.71239 + name "panel with tubes(14)" +} +PanelWithTubes { + translation 5.25302 1.06581e-14 -2.33772 + rotation 0 1 0 4.71239 + name "panel with tubes(15)" +} +PanelWithTubes { + translation 9.64302 1.06581e-14 -3.22772 + rotation 0 -1 0 4.71239 + name "panel with tubes(16)" +} +PanelWithTubes { + translation 5.25302 1.06581e-14 -3.22772 + rotation 0 1 0 4.71239 + name "panel with tubes(17)" +} +PanelWithTubes { + translation 8.33218 1.06581e-14 -3.68619 + rotation 0 1 0 3.14159 + name "panel with tubes(18)" +} +PanelWithTubes { + translation 8.33218 1.06581e-14 0.993814 + name "panel with tubes(19)" +} diff --git a/worlds/ros_python.wbt b/worlds/ros_python.wbt new file mode 100644 index 0000000..9a3cae5 --- /dev/null +++ b/worlds/ros_python.wbt @@ -0,0 +1,34 @@ +#VRML_SIM R2020b utf8 +WorldInfo { + info [ + "Simple Thymio II simulation controlled by a ROS node written in Python." + ] + title "ROS Python" + basicTimeStep 20 + coordinateSystem "NUE" + contactProperties [ + ContactProperties { + material2 "thymio body" + coulombFriction [ + 0.7 + ] + } + ] +} +Viewpoint { + orientation 0.3650235088419984 -0.9018337571390201 -0.2312005892665386 5.0279702 + position 0.85252477 0.55969193 0.54871339 + follow "Thymio II" +} +TexturedBackground { +} +TexturedBackgroundLight { +} +CircleArena { + wallThickness 0.05 +} +DEF THYMIO2 Thymio2 { + rotation 1 0 0 0 + controller "" + controllerArgs [] +} diff --git a/worlds/textures/floor.png b/worlds/textures/floor.png new file mode 100644 index 0000000..c80c394 Binary files /dev/null and b/worlds/textures/floor.png differ
Show message received from the controller: