Specification | Value |
---|---|
Wheel base | 1800 mm |
Rear Wheel track | 1545 mm |
Front Wheel track | 1280 mm |
Rear wheel radius | 500 mm |
Front wheel radius | 326 mm |
King pin width | 1500 mm |
Max steering angle | 30° |
Max speed | 15 km/h |
Tractor Agriculture Simulator is a ROS 2-based simulation environment for agricultural robotics research and development forsensor fusion, SLAM, navigation, and virtual field generation to enable the testing and development of autonomous agricultural robots in realistic scenarios.
Branch | Description |
---|---|
main | Used to test module like control and perception |
localization_test_bench | used to test different localization and odometry techniques with groundtruth odometery |
- Simulate tractors in virtual Agriculture fields with different crops type(Palm, Orange tree, Lemon tree).
- Sensor fusion using IMU and other sensors.
- 2D&3D SLAM with RTAB-Map.
- Teleoperation using Joystick.
- Customizable field/world generation.
src/tractor_description/
: Tractor robot model, URDF, meshes, and launch files.src/agri_robot_autonomous_pkg/
: contian the launch files for the odometry and visual SLAM.src/imu_tools/
: IMU filters and sensor fusion nodes.src/rtabmap_ros/
: RTAB-Map SLAM integration and demos.src/Simulation_Agriculture_Field_Generator/
: Virtual field/world generator.
- Install ROS 2 (Jazzy recommended)
- Clone this repository
- Install dependencies:
rosdep install --from-paths src --ignore-src -r -y
- Build the workspace for multi camera support:
colcon build --symlink-install --cmake-args -DRTABMAP_SYNC_MULTI_RGBD=ON -DRTABMAP_SYNC_USER_DATA=ON -DCMAKE_BUILD_TYPE=Release
- Source the workspace:
source install/setup.bash
ros2 launch virtual_maize_field simulation.launch.py
- To select a specific world:
ros2 run virtual_maize_field generate_world --crop_type natroon_palm --plant_spacing_min 7.0 --plant_spacing_max 7.1 --row_width 10.0 --row_segments straight --ground_resolution 0.5 --hole_size 0 --hole_prob 0 --ground_ditch_depth 0.0001 --ground_elevation_max 0.0001 --rows_count 3 --ground_headland 10
- copy
cp ~/.ros/virtual_maize_field/generated.world ~/tractor_agri_simulator/src/tractor_description/world/
source install/setup.bash
ros2 launch tractor_description gz_simulator_launch.py
source install/setup.bash
ros2 launch agri_robot_autonomous_pkg agri_robot_rgbd_scan_demo.launch.py localization:=false #ground_truth for removing the spawn shift from the ground truth odom
source install/setup.bash
ros2 launch teleop_twist_joy teleop-launch.py
- Field Generation: Use the tools in
Simulation_Agriculture_Field_Generator
to create custom fields. - Robot Models: Edit URDF and mesh files in
tractor_description
. - SLAM: Modify parameters in the respective config files.
Sensor Name | model | Type | Description | Usage |
---|---|---|---|---|
IMU | TD | IMU | Inertial Measurement Unit | fused with visual odometry |
NavSat | TD | GNSS/GPS | Global Navigation Satellite System | |
Front RGB-D | ZED2i | Camera (RGB-D) | Front stereo camera | Used to obtain visual odometry and mapping |
Left RGB-D | ZED2i | Camera (RGB-D) | Left stereo camera | Used to obtain visual odometry and mapping and used in object detection |
right RGB-D | ZED2i | Camera (RGB-D) | right stereo camera | Used to obtain visual odometry and mapping and used in object detection |
LIDAR | rplidar s2 | 2D LIDAR | Laser scanner | Fused with visual odometry to give better reading |
Topic Name | Message Type | Description |
---|---|---|
/imu | sensor_msgs/msg/Imu | IMU data |
/navsat | sensor_msgs/msg/NavSatFix | GNSS/GPS data |
/scan | sensor_msgs/msg/LaserScan | 2D LIDAR scan |
/front/rgb/image | sensor_msgs/msg/Image | Front RGB camera image |
/front/depth/image | sensor_msgs/msg/Image | Front depth camera image |
/front/rgb/camera_info | sensor_msgs/msg/CameraInfo | Front RGB camera info |
/left/rgb/image | sensor_msgs/msg/Image | Left RGB camera image |
/left/depth/image | sensor_msgs/msg/Image | Left depth camera image |
/left/rgb/camera_info | sensor_msgs/msg/CameraInfo | Left RGB camera info |
/right/rgb/image | sensor_msgs/msg/Image | Right RGB camera image |
/right/depth/image | sensor_msgs/msg/Image | Right depth camera image |
/right/rgb/camera_info | sensor_msgs/msg/CameraInfo | Right RGB camera info |
/cmd_vel | geometry_msgs/msg/Twist | Velocity command |
/tf | tf2_msgs/msg/TFMessage | Transforms |
/odom | nav_msgs/msg/Odometry | Ground truth odometry (sim) with spawn shift |
/clock | rosgraph_msgs/msg/Clock | Simulation clock |
Note: Topic names may be remapped in launch/config files. See
tractor_description/config/gz_bridge.yaml
and launch files for details.
Contributions are welcome! Please open issues and pull requests for bug fixes, new features, or documentation improvements.
- Ebrahim Abdelghafar ibrahim.abdelghafar@dakahlia.net
This project is licensed under the [TODO: License declaration].