![]() |
sjtu_drone repositorydrone gazebo ros2 gazebo-ros sjtu_drone_bringup sjtu_drone_control sjtu_drone_description |
Repository Summary
Description | ROS/ ROS 2 Gazebo quadcopter simulator. |
Checkout URI | https://github.com/novog93/sjtu_drone.git |
VCS Type | git |
VCS Version | ros2 |
Last Updated | 2025-02-07 |
Dev Status | UNKNOWN |
Released | UNRELEASED |
Tags | drone gazebo ros2 gazebo-ros |
Contributing |
Help Wanted (-)
Good First Issues (-) Pull Requests to Review (-) |
Packages
Name | Version |
---|---|
sjtu_drone_bringup | 0.0.0 |
sjtu_drone_control | 0.0.0 |
sjtu_drone_description | 0.0.0 |
README
sjtu_drone
sjtu_drone is a quadrotor simulation program forked from tum_simulator, developed using ROS + Gazebo.
The acronym ‘sjtu’ stands for Shanghai Jiao Tong University. This package has been used in the past for testing algorithms for the UAV contest at SJTU
Requirements
This package is tested with ROS 2 (Ubuntu 22.04) and Gazebo 11.
Downloading and building
cd ~/git && git clone git@github.com:NovoG93/sjtu_drone.git -b ros2
cd ~/ros2_ws/src && ln -s ~/git/sjtu_drone
cd .. && rosdep install -r -y --from-paths src --ignore-src --rosdistro $ROS_DISTRO && colcon build --packages-select-regex sjtu*
To use the playground.world file (as depicted below) make sure to install the common gazebo models, for more see the Readme in sjtu_drone_description.
Drone Topics
Sensors
The folowing sensors are currently implemented:
- ~/front/image_raw [sensor_msgs/msg/Image]
- ~/bottom/image_raw [sensor_msgs/msg/Image]
- ~/sonar/out [sensor_msgs/msg/Range]
- ~/imu/out [sensor_msgs/msg/Imu]
- ~/gps/nav [sensor_msgs/msg/NavSatFix]
- ~/gps/vel [geometry_msgs/msg/TwistStamped]
- ~/joint_states [sensor_msgs/msg/JointState]
Control
The following control topics are currently subscribed to:
- ~/cmd_vel [geometry_msgs/msg/Twist]: Steers the drone
- ~/land [std_msgs/msg/Empty]: Lands the drone
- ~/takeoff [std_msgs/msg/Empty]: Starts the drone
- ~/posctrl [std_msgs/msg/Bool]: Toggling between position control (give drone a pose via cmd_vel) and normal control (only use cmd_vel)
- ~/dronevel_mode [std_msgs/msg/Bool]: Toggeling between velocity and tilt control in normal control mode.
- ~/cmd_mode [std_msgs/msg/Bool]: Publishes the current control mode (position or normal control)
- ~/state [std_msgs/msg/Int8]: Publishes the current state of the drone (0: landed, 1: flying, 2: hovering)
- ~/reset [std_msgs/msg/Empty]: Resets the drone
Ground Truth
The following ground truth topics are currently published:
- ~/gt_acc [geometry_msgs/msg/Twist]: ground truth acceleration
- ~/gt_pose [geometry_msgs/msg/Pose]: ground truth pose
- ~/gt_vel [geometry_msgs/msg/Twist]: ground truth velocity
Configure Plugin
The plugin_drone
plugin is used to control the drone. It can be configured using the following parameters:
```yaml
ROS namespace for the drone. All topics and tf frames will be prefixed with this namespace.
namespace: /simple_drone
Proportional gain for roll and pitch PID controllers. Controls the drone’s response to roll and pitch errors.
rollpitchProportionalGain: 10.0
Differential gain for roll and pitch PID controllers. Helps to reduce overshoot and improve stability.
rollpitchDifferentialGain: 5.0
Maximum absolute value for roll and pitch control outputs, limiting maximum tilt angle.
rollpitchLimit: 0.5
Proportional gain for yaw PID controller. Determines how strongly the drone responds to yaw position errors.
yawProportionalGain: 2.0
Differential gain for yaw PID controller. Dampens the rate of change of yaw error for smoother rotation.
yawDifferentialGain: 1.0
Maximum absolute value for yaw control output, limiting rotational rate.
yawLimit: 1.5
Proportional gain for horizontal velocity PID controllers. Controls response to changes in horizontal velocity.
velocityXYProportionalGain: 5.0
Differential gain for horizontal velocity PID controllers. Controls acceleration/deceleration in horizontal plane.
velocityXYDifferentialGain: 2.3
Maximum limit for horizontal velocity control output, restricting maximum horizontal speed.
velocityXYLimit: 2
Proportional gain for vertical velocity PID controller. Influences response to altitude changes.
velocityZProportionalGain: 5.0
Integral gain for vertical velocity PID controller. Set to zero, indicating no error integration over time.
velocityZIntegralGain: 0.0
Differential gain for vertical velocity PID controller. Helps control vertical acceleration and deceleration.
velocityZDifferentialGain: 1.0
Maximum limit for vertical velocity control output. Negative value may indicate special control scenario or error.
velocityZLimit: -1
Proportional gain for horizontal position PID controllers. Controls response to horizontal displacement errors.
positionXYProportionalGain: 1.1
Differential gain for horizontal position PID controllers. Set to zero, meaning no rate of change consideration.
positionXYDifferentialGain: 0.0
Integral gain for horizontal position PID controllers. Set to zero, indicating no cumulative error correction.
positionXYIntegralGain: 0.0
Maximum limit for horizontal position control output, restricting maximum correctional force for horizontal errors.
positionXYLimit: 5
File truncated at 100 lines see the full file