├── origin_one_gazebo ├── origin_one_gazebo │ ├── __init__.py │ └── origin_specifics.py ├── resource │ └── origin_one_gazebo ├── setup.cfg ├── models │ ├── TY_test_area │ │ ├── materials │ │ │ └── textures │ │ │ │ ├── grass.jpg │ │ │ │ └── wood.jpg │ │ └── model.config │ ├── aruco_marker │ │ ├── materials │ │ │ ├── textures │ │ │ │ ├── aruco_0.png │ │ │ │ ├── aruco_10.png │ │ │ │ └── aruco_27.png │ │ │ └── scripts │ │ │ │ └── marker.material │ │ ├── model.config │ │ └── model.sdf │ └── avular_logo │ │ ├── materials │ │ ├── textures │ │ │ └── avular_logo.png │ │ └── scripts │ │ │ └── avular_logo.material │ │ ├── model.config │ │ └── model.sdf ├── package.xml ├── LICENSE ├── setup.py ├── launch │ ├── ty_test_area.launch.py │ └── origin_sim_common.launch.py ├── config │ └── gazebo_ros_bridge_topics.yaml └── worlds │ └── TY_test_area.world ├── .github └── CODEOWNERS ├── doc └── img │ └── simulation.png ├── .gitignore ├── cmd_vel_controller ├── loggercxx_3.0.0_amd64.deb ├── origin-msgs_1.0.0_amd64.deb ├── rclcpp-avular_3.0.0_amd64.deb └── cmd-vel-controller_1.7.1_amd64.deb ├── .gitmodules ├── LICENSE └── README.md /origin_one_gazebo/origin_one_gazebo/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /origin_one_gazebo/resource/origin_one_gazebo: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /.github/CODEOWNERS: -------------------------------------------------------------------------------- 1 | * @jorissijs @avupaul @tijsvdsmagt 2 | -------------------------------------------------------------------------------- /doc/img/simulation.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/avular-robotics/avular_origin_simulation/HEAD/doc/img/simulation.png -------------------------------------------------------------------------------- /.gitignore: -------------------------------------------------------------------------------- 1 | # Exceptions 2 | ## Folders 3 | build/* 4 | install/* 5 | log/* 6 | 7 | ## File types 8 | *.pyc 9 | 10 | .DS_Store 11 | -------------------------------------------------------------------------------- /origin_one_gazebo/setup.cfg: -------------------------------------------------------------------------------- 1 | [develop] 2 | script_dir=$base/lib/origin_one_gazebo 3 | [install] 4 | install_scripts=$base/lib/origin_one_gazebo 5 | -------------------------------------------------------------------------------- /cmd_vel_controller/loggercxx_3.0.0_amd64.deb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/avular-robotics/avular_origin_simulation/HEAD/cmd_vel_controller/loggercxx_3.0.0_amd64.deb -------------------------------------------------------------------------------- /cmd_vel_controller/origin-msgs_1.0.0_amd64.deb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/avular-robotics/avular_origin_simulation/HEAD/cmd_vel_controller/origin-msgs_1.0.0_amd64.deb -------------------------------------------------------------------------------- /cmd_vel_controller/rclcpp-avular_3.0.0_amd64.deb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/avular-robotics/avular_origin_simulation/HEAD/cmd_vel_controller/rclcpp-avular_3.0.0_amd64.deb -------------------------------------------------------------------------------- /.gitmodules: -------------------------------------------------------------------------------- 1 | [submodule "src/avular_origin_description"] 2 | path = src/avular_origin_description 3 | url = https://github.com/avular-robotics/avular_origin_description.git 4 | -------------------------------------------------------------------------------- /cmd_vel_controller/cmd-vel-controller_1.7.1_amd64.deb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/avular-robotics/avular_origin_simulation/HEAD/cmd_vel_controller/cmd-vel-controller_1.7.1_amd64.deb -------------------------------------------------------------------------------- /origin_one_gazebo/models/TY_test_area/materials/textures/grass.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/avular-robotics/avular_origin_simulation/HEAD/origin_one_gazebo/models/TY_test_area/materials/textures/grass.jpg -------------------------------------------------------------------------------- /origin_one_gazebo/models/TY_test_area/materials/textures/wood.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/avular-robotics/avular_origin_simulation/HEAD/origin_one_gazebo/models/TY_test_area/materials/textures/wood.jpg -------------------------------------------------------------------------------- /origin_one_gazebo/models/aruco_marker/materials/textures/aruco_0.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/avular-robotics/avular_origin_simulation/HEAD/origin_one_gazebo/models/aruco_marker/materials/textures/aruco_0.png -------------------------------------------------------------------------------- /origin_one_gazebo/models/aruco_marker/materials/textures/aruco_10.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/avular-robotics/avular_origin_simulation/HEAD/origin_one_gazebo/models/aruco_marker/materials/textures/aruco_10.png -------------------------------------------------------------------------------- /origin_one_gazebo/models/aruco_marker/materials/textures/aruco_27.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/avular-robotics/avular_origin_simulation/HEAD/origin_one_gazebo/models/aruco_marker/materials/textures/aruco_27.png -------------------------------------------------------------------------------- /origin_one_gazebo/models/avular_logo/materials/textures/avular_logo.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/avular-robotics/avular_origin_simulation/HEAD/origin_one_gazebo/models/avular_logo/materials/textures/avular_logo.png -------------------------------------------------------------------------------- /origin_one_gazebo/models/aruco_marker/materials/scripts/marker.material: -------------------------------------------------------------------------------- 1 | material Marker 2 | { 3 | technique 4 | { 5 | pass 6 | { 7 | texture_unit 8 | { 9 | texture aruco_27.png 10 | filtering anisotropic 11 | max_anisotropy 16 12 | } 13 | } 14 | } 15 | } 16 | -------------------------------------------------------------------------------- /origin_one_gazebo/models/TY_test_area/model.config: -------------------------------------------------------------------------------- 1 | 2 | 3 | TY_test_area 4 | 1.0 5 | model.sdf 6 | 7 | Joris Sijs 8 | j.sijs@avular.com 9 | 10 | 11 | 12 | -------------------------------------------------------------------------------- /origin_one_gazebo/models/avular_logo/model.config: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | avular_logo 5 | 1.0 6 | model.sdf 7 | 8 | 9 | Joris Sijs 10 | j.sijs@avular.com 11 | 12 | 13 | 14 | Avular logo as a wall. 15 | 16 | 17 | 18 | -------------------------------------------------------------------------------- /origin_one_gazebo/models/aruco_marker/model.config: -------------------------------------------------------------------------------- 1 | 2 | 3 | Aruco Marker 4 | 0.1.0 5 | model.sdf 6 | 7 | 8 | Tarun Sriram 9 | t.sriram@avular.com 10 | 11 | 12 | Avular Confidential 13 | 14 | 15 |

Aruco Marker

16 |
17 |
18 | -------------------------------------------------------------------------------- /origin_one_gazebo/models/avular_logo/materials/scripts/avular_logo.material: -------------------------------------------------------------------------------- 1 | material vrc/avular_logo 2 | { 3 | receive_shadows on 4 | technique 5 | { 6 | pass 7 | { 8 | ambient 0.8 1.0 0.8 1.0 9 | diffuse 0.8 1.0 0.8 1.0 10 | specular 0.1 0.1 0.1 1.0 12.5 11 | 12 | texture_unit 13 | { 14 | texture avular_logo.png 15 | filtering anistropic 16 | max_anisotropy 16 17 | } 18 | } 19 | } 20 | } 21 | -------------------------------------------------------------------------------- /origin_one_gazebo/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | origin_one_gazebo 5 | 0.0.0 6 | Gazebo simulation models for the Avular Origin V1.0 7 | Joris Sijs 8 | Tijs van der Smagt 9 | Bob Hendrikx 10 | proprietary 11 | 12 | cmd_vel_controller 13 | origin_one_description 14 | ros_gz_sim 15 | ros_gz_bridge 16 | std_msgs 17 | sensor_msgs 18 | std_srvs 19 | tf2_ros 20 | 21 | ament_copyright 22 | ament_flake8 23 | ament_pep257 24 | python3-pytest 25 | 26 | 27 | ament_python 28 | 29 | 30 | -------------------------------------------------------------------------------- /origin_one_gazebo/models/avular_logo/model.sdf: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | true 5 | 6 | 7 | 8 | 9 | 0 0 1 10 | 500 500 11 | 12 | 13 | 14 | 15 | 16 | 0.5 17 | .5 18 | 19 | 20 | 21 | 22 | 23 | 24 | 0 0 0 0 0 0 25 | 26 | false 27 | 28 | 29 | 0 0 1 30 | 10 10 31 | 32 | 33 | 34 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | 46 | -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- 1 | Copyright 2024 Avular 2 | 3 | Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: 4 | 5 | 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. 6 | 7 | 2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. 8 | 9 | 3. Neither the name of the copyright holder nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission. 10 | 11 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS “AS IS” AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 12 | -------------------------------------------------------------------------------- /origin_one_gazebo/LICENSE: -------------------------------------------------------------------------------- 1 | Copyright 2024 Avular 2 | 3 | Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: 4 | 5 | 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. 6 | 7 | 2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. 8 | 9 | 3. Neither the name of the copyright holder nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission. 10 | 11 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS “AS IS” AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 12 | -------------------------------------------------------------------------------- /origin_one_gazebo/models/aruco_marker/model.sdf: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | true 5 | 6 | 7 | 0 0 0 0 0 0 8 | 0.001 9 | 10 | 3.7499999999999997e-06 11 | 0.0 12 | 0.0 13 | 1.8750008333333333e-06 14 | 0.0 15 | 1.8750008333333333e-06 16 | 17 | 18 | 19 | 0.00005 0 0 0 0 0 20 | 21 | 22 | 0.0001 0.4 0.4 23 | 24 | 25 | 26 | 1.0 1.0 1.0 27 | 1.0 1.0 1.0 28 | 29 | 30 | model://aruco_marker/materials/textures/aruco_27.png 31 | model://aruco_marker/materials/textures/aruco_27.png 32 | 33 | 34 | 35 | 36 | 37 | 38 | -0.00005 0 0 0 0 0 39 | 40 | 41 | 0.0001 0.4 0.4 42 | 43 | 44 | 45 | 46 | 0 0 0 0 0 0 47 | 48 | 49 | 0.0001 0.4 0.4 50 | 51 | 52 | 53 | 54 | 55 | 56 | -------------------------------------------------------------------------------- /origin_one_gazebo/setup.py: -------------------------------------------------------------------------------- 1 | import os # Operating system library 2 | from glob import glob # Handles file path names 3 | from setuptools import setup # Facilitates the building of packages 4 | 5 | package_name = "origin_one_gazebo" 6 | 7 | # Path of the current directory 8 | cur_directory_path = os.path.abspath(os.path.dirname(__file__)) 9 | 10 | # Get all the gazebo models recursively and keep the directory structure 11 | model_src_paths = glob("models/**/*.*", recursive=True) 12 | model_dest_paths = [ 13 | os.path.join("share", package_name, os.path.dirname(path)) 14 | for path in model_src_paths 15 | ] 16 | 17 | data_files = list(zip(model_dest_paths, [[path] for path in model_src_paths])) 18 | 19 | data_files.extend( 20 | [ 21 | ("share/" + package_name, ["package.xml"]), 22 | ("share/ament_index/resource_index/packages", ["resource/" + package_name]), 23 | # Path to the launch file 24 | (os.path.join("share", package_name, "launch"), glob("launch/*.launch.py")), 25 | # Path to the world file 26 | (os.path.join("share", package_name, "worlds/"), glob("./worlds/*")), 27 | # (os.path.join('share', package_name,'models/'), glob('./models/**/*.*', recursive=True)), 28 | # Path to the config files 29 | (os.path.join("share", package_name, "config/"), glob("./config/*")), 30 | ] 31 | ) 32 | 33 | setup( 34 | name=package_name, 35 | version="0.0.0", 36 | packages=[package_name], 37 | data_files=data_files, 38 | install_requires=["setuptools"], 39 | zip_safe=True, 40 | maintainer="Joris Sijs", 41 | maintainer_email="j.sijs@avular.com", 42 | description="Simulation environment for the Avular Origin V1.0", 43 | license="TODO: License declaration", 44 | tests_require=["pytest"], 45 | entry_points={ 46 | "console_scripts": [ 47 | "robot_specifics = origin_one_gazebo.origin_specifics:main", 48 | ], 49 | }, 50 | ) 51 | -------------------------------------------------------------------------------- /origin_one_gazebo/origin_one_gazebo/origin_specifics.py: -------------------------------------------------------------------------------- 1 | # Copyright 2024 Avular B.V. 2 | # All Rights Reserved 3 | # You may use this code under the terms of the Avular 4 | # Software End-User License Agreement. 5 | # 6 | # You should have received a copy of the Avular 7 | # Software End-User License Agreement license with 8 | # this file, or download it from: avular.com/eula 9 | 10 | import rclpy 11 | from rclpy.node import Node 12 | 13 | from std_srvs.srv import Trigger 14 | from std_msgs.msg import Bool 15 | from sensor_msgs.msg import NavSatFix, Image, CameraInfo 16 | 17 | class AvularTopics(Node): 18 | 19 | def __init__(self): 20 | super().__init__('avular_specific_topics') 21 | # create publisher for 'faking' the emergency brake 22 | self.publisher_ebrake = self.create_publisher(Bool, 'robot/safety_supervisor/emergency_brake_active', 10) 23 | timer_period = 1.0 # seconds 24 | self.timer = self.create_timer(timer_period, self.timer_callback) 25 | self.emergency_brake = Bool() 26 | #create service 27 | self.srv = self.create_service(Trigger, 'robot/set_obstacle_avoidance', self.set_avoidance_callback) 28 | 29 | def set_avoidance_callback(self, request, response): 30 | response.success = True 31 | #self.get_logger().info('setting obstacle avoidance to "%s"' % request.trigger) 32 | return response 33 | 34 | def timer_callback(self): 35 | self.emergency_brake.data = False 36 | self.publisher_ebrake.publish(self.emergency_brake) 37 | #self.get_logger().info('Publishing: "%s"' % msg.data) 38 | 39 | 40 | def main(args=None): 41 | rclpy.init(args=args) 42 | 43 | avular_specific_topics = AvularTopics() 44 | 45 | rclpy.spin(avular_specific_topics) 46 | 47 | # Destroy the node explicitly 48 | # (optional - otherwise it will be done automatically 49 | # when the garbage collector destroys the node object) 50 | minimal_publisher.destroy_node() 51 | rclpy.shutdown() 52 | 53 | 54 | if __name__ == '__main__': 55 | main() 56 | -------------------------------------------------------------------------------- /origin_one_gazebo/launch/ty_test_area.launch.py: -------------------------------------------------------------------------------- 1 | # Copyright 2024 Avular B.V. 2 | # All Rights Reserved 3 | # You may use this code under the terms of the Avular 4 | # Software End-User License Agreement. 5 | # 6 | # You should have received a copy of the Avular 7 | # Software End-User License Agreement license with 8 | # this file, or download it from: avular.com/eula 9 | 10 | from launch import LaunchDescription 11 | from launch.actions import ( 12 | DeclareLaunchArgument, 13 | IncludeLaunchDescription, 14 | SetLaunchConfiguration, 15 | ) 16 | from launch.launch_description_sources import PythonLaunchDescriptionSource 17 | from launch.substitutions import PathJoinSubstitution, LaunchConfiguration 18 | from launch_ros.substitutions import FindPackageShare 19 | 20 | 21 | def generate_launch_description(): 22 | set_world_file_name = SetLaunchConfiguration( 23 | "world_file_name", "TY_test_area.world" 24 | ) 25 | robot_pose_x = SetLaunchConfiguration("robot_pose_x", "-18.75") 26 | robot_pose_y = SetLaunchConfiguration("robot_pose_y", "-34.8") 27 | robot_pose_yaw = SetLaunchConfiguration("robot_pose_yaw", "1.57") 28 | 29 | drive_configuration = DeclareLaunchArgument( 30 | "drive_configuration", default_value="skid_steer_drive") 31 | 32 | launch_origin_common = IncludeLaunchDescription( 33 | PythonLaunchDescriptionSource( 34 | [ 35 | PathJoinSubstitution( 36 | [ 37 | FindPackageShare("origin_one_gazebo"), 38 | "launch", 39 | "origin_sim_common.launch.py", 40 | ] 41 | ) 42 | ] 43 | ), 44 | launch_arguments={ 45 | "drive_configuration": LaunchConfiguration("drive_configuration") 46 | }.items(), 47 | ) 48 | 49 | return LaunchDescription( 50 | [ 51 | set_world_file_name, 52 | robot_pose_x, 53 | robot_pose_y, 54 | robot_pose_yaw, 55 | drive_configuration, 56 | launch_origin_common, 57 | ] 58 | ) 59 | -------------------------------------------------------------------------------- /origin_one_gazebo/config/gazebo_ros_bridge_topics.yaml: -------------------------------------------------------------------------------- 1 | - ros_topic_name: "clock" 2 | gz_topic_name: "clock" 3 | ros_type_name: "rosgraph_msgs/msg/Clock" 4 | gz_type_name: "gz.msgs.Clock" 5 | direction: GZ_TO_ROS 6 | 7 | - ros_topic_name: "tf" 8 | gz_topic_name: "/robot/tf" 9 | ros_type_name: "tf2_msgs/msg/TFMessage" 10 | gz_type_name: "gz.msgs.Pose_V" 11 | direction: GZ_TO_ROS 12 | 13 | - ros_topic_name: "/robot/cmd_vel" 14 | gz_topic_name: "/robot/cmd_vel" 15 | ros_type_name: "geometry_msgs/msg/Twist" 16 | gz_type_name: "gz.msgs.Twist" 17 | subscriber_queue: 5 18 | publisher_queue: 6 19 | lazy: true 20 | direction: 21 | ROS_TO_GZ 22 | 23 | - ros_topic_name: "/robot/odom" 24 | gz_topic_name: "/robot/odom" 25 | ros_type_name: "nav_msgs/msg/Odometry" 26 | gz_type_name: "gz.msgs.Odometry" 27 | subscriber_queue: 5 28 | publisher_queue: 6 29 | lazy: true 30 | direction: 31 | GZ_TO_ROS 32 | 33 | - ros_topic_name: "/robot/gnss/fix_off" 34 | gz_topic_name: "/robot/gnss" 35 | ros_type_name: "sensor_msgs/msg/NavSatFix" 36 | gz_type_name: "gz.msgs.NavSat" 37 | subscriber_queue: 5 38 | publisher_queue: 6 39 | lazy: true 40 | direction: 41 | GZ_TO_ROS 42 | 43 | - ros_topic_name: "/robot/camera/color/camera_info" 44 | gz_topic_name: "/robot/camera/camera_info" 45 | ros_type_name: "sensor_msgs/msg/CameraInfo" 46 | gz_type_name: "gz.msgs.CameraInfo" 47 | direction: GZ_TO_ROS 48 | 49 | - ros_topic_name: "/robot/camera/color/image_raw" 50 | gz_topic_name: "/robot/camera/image" 51 | ros_type_name: "sensor_msgs/msg/Image" 52 | gz_type_name: "gz.msgs.Image" 53 | subscriber_queue: 1 54 | publisher_queue: 1 55 | lazy: true 56 | direction: 57 | GZ_TO_ROS 58 | 59 | - ros_topic_name: "/robot/camera/depth/image_raw" 60 | gz_topic_name: "/robot/camera/depth_image" 61 | ros_type_name: "sensor_msgs/msg/Image" 62 | gz_type_name: "gz.msgs.Image" 63 | subscriber_queue: 1 64 | publisher_queue: 1 65 | lazy: true 66 | direction: 67 | GZ_TO_ROS 68 | 69 | - ros_topic_name: "/robot/camera/depth/points" 70 | gz_topic_name: "/robot/camera/points" 71 | ros_type_name: "sensor_msgs/msg/PointCloud2" 72 | gz_type_name: "gz.msgs.PointCloudPacked" 73 | subscriber_queue: 1 74 | publisher_queue: 1 75 | lazy: true 76 | direction: 77 | GZ_TO_ROS 78 | 79 | - ros_topic_name: "/robot/lidar/points" 80 | gz_topic_name: "/robot/lidar/points" 81 | ros_type_name: "sensor_msgs/msg/PointCloud2" 82 | gz_type_name: "gz.msgs.PointCloudPacked" 83 | subscriber_queue: 1 84 | publisher_queue: 1 85 | lazy: true 86 | direction: 87 | GZ_TO_ROS 88 | 89 | - ros_topic_name: "/robot/joint_states" 90 | gz_topic_name: "/robot/joint_states" 91 | ros_type_name: "sensor_msgs/msg/JointState" 92 | gz_type_name: "gz.msgs.Model" 93 | subscriber_queue: 1 94 | publisher_queue: 1 95 | lazy: true 96 | direction: 97 | GZ_TO_ROS 98 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # Avular Origin simulation 2 | 3 | This repository contains the simulation environment for the Avular Origin One, using Gazebo Fortress and ROS2 Humble. 4 | 5 | ## Getting started 6 | 7 | We currently only support ROS2 Humble on Ubuntu 22.04. For installing ROS2 Humble on your system, refer to the [ROS2 Humble installation guide](https://docs.ros.org/en/humble/Installation.html). 8 | After making sure that ROS2 Humble is installed, install Gazebo Fortress on your system: 9 | 10 | ``` 11 | sudo apt update 12 | sudo apt install ros-humble-ros-gz git-lfs 13 | ``` 14 | 15 | To get started with the Avular Origin Simulation, first make a ROS workspace on your computer (for instructions, see [the ROS tutorial](https://docs.ros.org/en/humble/Tutorials/Beginner-Client-Libraries/Creating-A-Workspace/Creating-A-Workspace.html)). 16 | Next, go to the 'src' folder of your workspace and clone this repository: 17 | 18 | ``` 19 | cd /src 20 | git clone -b origin_1.0/1 https://github.com/avular-robotics/avular_origin_simulation.git 21 | ``` 22 | 23 | In the same `src` folder, we also need to clone the `avular_origin_description` repository, which contains the URDF and meshes for the Origin One robot: 24 | ``` 25 | git clone https://github.com/avular-robotics/avular_origin_description.git 26 | cd avular_origin_description 27 | git lfs pull 28 | ``` 29 | 30 | Finally, we can install debian packages for the cmd_vel_controller, which the real Origin One robot uses to prioritize various control command inputs. 31 | This step is optional, but recommended if you want the simulation to behave similar to the real robot, or if you want to use Avular example code. 32 | To do so, go to the `cmd_vel_controller` folder in this repository and use `apt` to install the binary packages: 33 | 34 | ``` 35 | cd /src/avular_origin_simulation/cmd_vel_controller/ 36 | sudo apt install ./loggercxx_3.0.0_amd64.deb ./rclcpp-avular_3.0.0_amd64.deb ./origin-msgs_1.0.0_amd64.deb ./cmd-vel-controller_1.7.1_amd64.deb 37 | ``` 38 | 39 | Next, go to the top level workspace folder and build the packages in the workspace: 40 | ``` 41 | cd 42 | colcon build --symlink-install 43 | ``` 44 | 45 | This will generate a warning that easy_install is deprecated, which can be ignored. 46 | 47 | You can now source the workspace (so ROS knows where to find the packages) and launch the simulation environment: 48 | ``` 49 | source install/setup.bash 50 | ros2 launch origin_one_gazebo ty_test_area.launch.py use_cmd_vel_controller:=True 51 | ``` 52 | Note that you can set `use_cmd_vel_controller` to `False` if you don't want to use the cmd_vel_controller package. 53 | Alternatively, the simulation can also be launched with the mecanum wheel configuration on the robot: 54 | ``` 55 | ros2 launch origin_one_gazebo ty_test_area.launch.py use_cmd_vel_controller:=True drive_configuration:=mecanum_drive 56 | ``` 57 | This will show the avular simulation environment in Gazebo Fortress, with the Origin One spawned. 58 | You can now drag to mouse to change the view to the robot model. 59 | If you want to launch the simulation without sourcing each time, you can source the setup file in your bashrc: 60 | ``` 61 | echo "source /install/setup.bash" >> ~/.bashrc 62 | ``` 63 | 64 | ![image](./doc/img/simulation.png) 65 | 66 | ## Driving and visualizing the robot in the simulation 67 | 68 | The simulation contains gazebo plugins for the drive controller, the Ouster LiDAR and the realsense camera. To visualize the robot and its sensors, you can use the RViz visualization tool. To launch RViz with the correct configuration, run the following command: 69 | ``` 70 | ros2 launch origin_one_description origin_one_rviz.launch.py 71 | ``` 72 | 73 | This will open RViz with the robot model and the sensor data. You can now drive the robot around in the simulation by publishing Twist messages to the `/robot/cmd_vel` topic. For example by using the `teleop_twist_keyboard` package: 74 | ``` 75 | sudo apt install ros-humble-teleop-twist-keyboard 76 | ros2 run teleop_twist_keyboard teleop_twist_keyboard --ros-args -r /cmd_vel:=/robot/cmd_vel 77 | ``` 78 | 79 | -------------------------------------------------------------------------------- /origin_one_gazebo/worlds/TY_test_area.world: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | EARTH_WGS84 7 | ENU 8 | 51.453423125136865 9 | 5.448826930660351 10 | 0 11 | 0 12 | 13 | 14 | 15 | 0.01 16 | 1.0 17 | 18 | 21 | 22 | 25 | 26 | 29 | 30 | 31 | 32 | 1 33 | 0 0 10 0 -0 0 34 | 0.8 0.8 0.8 1 35 | 0.2 0.2 0.2 1 36 | 37 | 1000 38 | 0.9 39 | 0.01 40 | 0.001 41 | 42 | 0.5 0.1 -0.9 43 | 44 | 45 | 46 | 1 47 | 48 | 49 | 50 | 51 | 0 0 1 52 | 200 200 53 | 54 | 55 | 56 | 57 | 58 | 100 59 | 50 60 | 61 | 62 | 63 | 64 | 65 | 66 | 67 | 10 68 | 69 | 70 | 0 71 | 72 | 73 | 0 0 1 74 | 200 200 75 | 76 | 77 | 78 | 0.5 0.5 0.5 1.0 79 | 0.5 0.5 0.5 1.0 80 | 0.5 0.5 0.5 1.0 81 | 82 | 83 | 84 | 0 85 | 0 86 | 87 | 0 88 | 0 89 | 1 90 | 91 | 92 | 93 | 94 | 0.4 0.4 0.4 1 95 | 0.7 0.7 0.7 1 96 | 0 97 | 98 | 99 | 100 | 101 | 0 0 102 | 0 44986 103 | 1377677575 940727583 104 | 105 | 106 | 107 | 108 | -18.75 -34.0 12.2 0 1.56 3.14 109 | orbit 110 | 111 | 112 | 113 | 114 | 115 | 116 | model://TY_test_area 117 | track1 118 | 0.0 0.0 2.5 0 0 0 119 | 120 | 121 | 122 | 123 | model://aruco_marker 124 | aurco_marker 125 | -18.75 -32.6 0.2 0 0 -1.5707 126 | 127 | 128 | 129 | https://fuel.gazebosim.org/1.0/OpenRobotics/models/Bookshelf 130 | bookshelf_2 131 | -14.70 -41.9 0.2 0 0 1.45 132 | 133 | 134 | https://fuel.gazebosim.org/1.0/OpenRobotics/models/Bookshelf 135 | bookshelf_1 136 | -14.60 -43.0 0.2 0 0 1.45 137 | 138 | 139 | https://fuel.gazebosim.org/1.0/OpenRobotics/models/Bookshelf 140 | bookshelf_3 141 | -14.50 -44.2 0.2 0 0 1.5 142 | 143 | 144 | https://fuel.gazebosim.org/1.0/OpenRobotics/models/Bookshelf 145 | bookshelf_5 146 | -14.30 -45.3 0.2 0 0 1.52 147 | 148 | 149 | https://fuel.gazebosim.org/1.0/OpenRobotics/models/Bookshelf 150 | bookshelf_4 151 | -14.65 -46.3 0.2 0 0 1.57 152 | 153 | 154 | 155 | 156 | https://fuel.gazebosim.org/1.0/OpenRobotics/models/SUV 157 | suv_1 158 | -13.50 -49.3 0.0 0 0 -1.5707 159 | 160 | 161 | 162 | 163 | https://fuel.gazebosim.org/1.0/OpenRobotics/models/Asphalt Plane 164 | road_1 165 | 22.5 -2.5 0.9 0 0 0 166 | 167 | 168 | https://fuel.gazebosim.org/1.0/OpenRobotics/models/Asphalt Plane 169 | road_2 170 | 22.5 17.5 0.9 0 0 0 171 | 172 | 173 | https://fuel.gazebosim.org/1.0/OpenRobotics/models/Asphalt Plane 174 | road_3 175 | 22.5 37.5 0.9 0 0 0 176 | 177 | 178 | https://fuel.gazebosim.org/1.0/OpenRobotics/models/Asphalt Plane 179 | road_4 180 | 22.5 -22.5 0.9 0 0 0 181 | 182 | 183 | https://fuel.gazebosim.org/1.0/OpenRobotics/models/Asphalt Plane 184 | road_5 185 | 22.5 -42.5 0.9 0 0 0 186 | 187 | 188 | https://fuel.gazebosim.org/1.0/OpenRobotics/models/Asphalt Plane 189 | road_6 190 | 22.5 52.5 0.9 0 0 0 191 | 192 | 193 | https://fuel.gazebosim.org/1.0/OpenRobotics/models/Asphalt Plane 194 | road_7 195 | 2.5 52.5 0.9 0 0 0 196 | 197 | 198 | https://fuel.gazebosim.org/1.0/OpenRobotics/models/Asphalt Plane 199 | road_8 200 | -17.5 52.5 0.9 0 0 0 201 | 202 | 203 | https://fuel.gazebosim.org/1.0/OpenRobotics/models/Asphalt Plane 204 | road_9 205 | -37.5 52.5 0.9 0 0 0 206 | 207 | 208 | 209 | 210 | -------------------------------------------------------------------------------- /origin_one_gazebo/launch/origin_sim_common.launch.py: -------------------------------------------------------------------------------- 1 | # Copyright 2024 Avular B.V. 2 | # All Rights Reserved 3 | # You may use this code under the terms of the Avular 4 | # Software End-User License Agreement. 5 | # 6 | # You should have received a copy of the Avular 7 | # Software End-User License Agreement license with 8 | # this file, or download it from: avular.com/eula 9 | 10 | import os 11 | from launch import LaunchDescription 12 | from launch.substitutions import LaunchConfiguration, PathJoinSubstitution 13 | from launch_ros.substitutions import FindPackageShare 14 | from launch_ros.actions import Node 15 | from launch.conditions import IfCondition, UnlessCondition 16 | from launch.actions import ( 17 | ExecuteProcess, 18 | DeclareLaunchArgument, 19 | IncludeLaunchDescription, 20 | OpaqueFunction, 21 | SetLaunchConfiguration 22 | ) 23 | from ament_index_python.packages import get_package_share_directory 24 | from launch.launch_description_sources import PythonLaunchDescriptionSource 25 | import xacro 26 | 27 | 28 | def generate_launch_description(): 29 | ld = LaunchDescription() 30 | 31 | ld.add_action(DeclareLaunchArgument("headless", default_value="false")) 32 | ld.add_action(DeclareLaunchArgument("spawn", default_value="true")) 33 | ld.add_action(DeclareLaunchArgument("world", default_value="TY_test_area.world")) 34 | ld.add_action(DeclareLaunchArgument("drive_configuration", default_value="skid_steer_drive")) 35 | ld.add_action( 36 | DeclareLaunchArgument( 37 | "bridge_config", default_value="gazebo_ros_bridge_topics.yaml" 38 | ) 39 | ) 40 | ld.add_action( 41 | DeclareLaunchArgument("use_cmd_vel_controller", default_value="False") 42 | ) 43 | ld.add_action(DeclareLaunchArgument("robot_pose_x", default_value="0.0")) 44 | ld.add_action(DeclareLaunchArgument("robot_pose_y", default_value="0.0")) 45 | ld.add_action(DeclareLaunchArgument("robot_pose_yaw", default_value="0.0")) 46 | 47 | ros_gz_sim = get_package_share_directory("ros_gz_sim") 48 | pkg_dir = get_package_share_directory("origin_one_gazebo") 49 | pkg_dir_origin_description = get_package_share_directory("origin_one_description") 50 | xacro_file_path = "urdf/origin_one.urdf.xacro" 51 | 52 | os.environ["IGN_GAZEBO_RESOURCE_PATH"] = ( 53 | os.path.join(pkg_dir, "models") 54 | + os.pathsep 55 | + os.path.join(pkg_dir_origin_description, "..") 56 | ) 57 | 58 | world = PathJoinSubstitution([pkg_dir, "worlds", LaunchConfiguration("world")]) 59 | 60 | ld.add_action( 61 | IncludeLaunchDescription( 62 | PythonLaunchDescriptionSource( 63 | os.path.join(ros_gz_sim, "launch", "gz_sim.launch.py") 64 | ), 65 | launch_arguments={ 66 | "gz_args": ["-r -s -v1 ", world], 67 | "on_exit_shutdown": "true", 68 | }.items(), 69 | ) 70 | ) 71 | 72 | ld.add_action( 73 | ExecuteProcess( 74 | cmd=["ign", "gazebo", "-g", "-v1"], 75 | condition=UnlessCondition(LaunchConfiguration("headless")), 76 | ) 77 | ) 78 | 79 | sdf_file_path = PathJoinSubstitution( 80 | [pkg_dir_origin_description, "urdf", "origin_one.urdf"] 81 | ) 82 | 83 | # Function to create the URDF description from the Xacro file 84 | def create_urdf_description(context): 85 | xacro_file = os.path.join(FindPackageShare("origin_one_description").find("origin_one_description"), xacro_file_path) 86 | drive_configuration = LaunchConfiguration('drive_configuration').perform(context) 87 | urdf = xacro.process_file(xacro_file, mappings={"drive_configuration": drive_configuration}).toxml() 88 | return [SetLaunchConfiguration('urdf', urdf)] 89 | 90 | ld.add_action(OpaqueFunction(function=create_urdf_description)) 91 | 92 | ld.add_action( 93 | Node( 94 | package="ros_gz_sim", 95 | executable="create", 96 | arguments=[ 97 | "-name", 98 | "Robot", 99 | "-string", 100 | LaunchConfiguration("urdf"), 101 | "-x", 102 | LaunchConfiguration("robot_pose_x"), 103 | "-y", 104 | LaunchConfiguration("robot_pose_y"), 105 | "-z", 106 | "1.0", 107 | "-Y", 108 | LaunchConfiguration("robot_pose_yaw"), 109 | ], 110 | output="screen", 111 | condition=IfCondition(LaunchConfiguration("spawn")), 112 | ) 113 | ) 114 | 115 | bridge_config_file = PathJoinSubstitution( 116 | [ 117 | pkg_dir, 118 | "config", 119 | LaunchConfiguration("bridge_config"), 120 | ] 121 | ) 122 | 123 | ld.add_action( 124 | Node( 125 | package="ros_gz_bridge", 126 | executable="parameter_bridge", 127 | name="ros_gz_bridge", 128 | output="screen", 129 | parameters=[ 130 | { 131 | "config_file": bridge_config_file, 132 | "qos_overrides./robot/cmd_vel.subscription.reliability": "best_effort", 133 | } 134 | ], 135 | ) 136 | ) 137 | 138 | ld.add_action( 139 | IncludeLaunchDescription( 140 | PythonLaunchDescriptionSource( 141 | os.path.join(pkg_dir_origin_description, "launch", "origin_one_description.launch.py") 142 | ) 143 | ) 144 | ) 145 | ld.add_action( 146 | Node( 147 | package="origin_one_gazebo", 148 | executable="robot_specifics", 149 | arguments=[], 150 | output="screen", 151 | ) 152 | ) 153 | ld.add_action( 154 | Node( 155 | package="tf2_ros", 156 | executable="static_transform_publisher", 157 | arguments=[ 158 | "0.0", 159 | "0.0", 160 | "0.0", 161 | "0.0", 162 | "0.0", 163 | "0.0", 164 | "camera_link", 165 | "camera_color_frame", 166 | ], 167 | output="screen", 168 | ) 169 | ) 170 | ld.add_action( 171 | Node( 172 | package="tf2_ros", 173 | executable="static_transform_publisher", 174 | arguments=[ 175 | "0.0", 176 | "0.0", 177 | "0.0", 178 | "-1.5707", 179 | "0.0", 180 | "-1.5707", 181 | "camera_color_frame", 182 | "camera_color_optical_frame", 183 | ], 184 | output="screen", 185 | ) 186 | ) 187 | ld.add_action( 188 | Node( 189 | package="tf2_ros", 190 | executable="static_transform_publisher", 191 | arguments=[ 192 | "0.0", 193 | "0.0", 194 | "0.0", 195 | "0.0", 196 | "0.0", 197 | "0.0", 198 | "camera_link", 199 | "camera_depth_frame", 200 | ], 201 | output="screen", 202 | ) 203 | ) 204 | ld.add_action( 205 | Node( 206 | package="tf2_ros", 207 | executable="static_transform_publisher", 208 | arguments=[ 209 | "0.0", 210 | "0.0", 211 | "0.0", 212 | "-1.5707", 213 | "0.0", 214 | "-1.5707", 215 | "camera_color_frame", 216 | "camera_depth_optical_frame", 217 | ], 218 | output="screen", 219 | ) 220 | ) 221 | ld.add_action( 222 | Node( 223 | package="tf2_ros", 224 | executable="static_transform_publisher", 225 | arguments=[ 226 | "0.006253", 227 | "-0.011775", 228 | "0.007645", 229 | "0.0", 230 | "0.0", 231 | "0.0", 232 | "os_sensor", 233 | "os_imu", 234 | ], 235 | output="screen", 236 | ) 237 | ) 238 | ld.add_action( 239 | Node( 240 | package="tf2_ros", 241 | executable="static_transform_publisher", 242 | arguments=[ 243 | "0.0", 244 | "0.0", 245 | "0.03618", 246 | "0.0", 247 | "0.0", 248 | "0.0", 249 | "os_sensor", 250 | "os_lidar", 251 | ], 252 | output="screen", 253 | ) 254 | ) 255 | 256 | # cmd_vel_controller to prioritize control commands 257 | ld.add_action( 258 | Node( 259 | condition=IfCondition(LaunchConfiguration("use_cmd_vel_controller")), 260 | package="cmd_vel_controller", 261 | executable="cmd_vel_controller", 262 | name="cmd_vel_controller", 263 | namespace="robot", 264 | parameters=[PathJoinSubstitution([pkg_dir_origin_description, "config", "cmd_vel_controller.yaml"])], 265 | respawn=True, 266 | respawn_delay=1.0, 267 | ) 268 | ) 269 | 270 | return ld 271 | --------------------------------------------------------------------------------