Skip to content

Commit 4959098

Browse files
perrrreClaudio-Chies
authored andcommitted
Add gz model for quadtailsitter (PX4#23943)
* Add gazebo airspeed plugin and add a tailsitter model --------- Co-authored-by: Claudio Chies <[email protected]>
1 parent f02bf4b commit 4959098

5 files changed

Lines changed: 108 additions & 12 deletions

File tree

Lines changed: 97 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,97 @@
1+
#!/bin/sh
2+
#
3+
# @name Quadrotor + Tailsitter
4+
#
5+
# @type VTOL Quad Tailsitter
6+
#
7+
8+
. ${R}etc/init.d/rc.vtol_defaults
9+
10+
PX4_SIMULATOR=${PX4_SIMULATOR:=gz}
11+
PX4_GZ_WORLD=${PX4_GZ_WORLD:=default}
12+
PX4_SIM_MODEL=${PX4_SIM_MODEL:=quadtailsitter}
13+
14+
param set-default SIM_GZ_EN 1 # Gazebo bridge
15+
16+
param set-default SENS_EN_GPSSIM 1
17+
param set-default SENS_EN_BAROSIM 0
18+
param set-default SENS_EN_MAGSIM 1
19+
param set-default SENS_EN_ARSPDSIM 0
20+
21+
22+
param set-default MAV_TYPE 20
23+
24+
param set-default CA_AIRFRAME 4
25+
26+
param set-default CA_ROTOR_COUNT 4
27+
param set-default CA_ROTOR0_PX 0.15
28+
param set-default CA_ROTOR0_PY 0.23
29+
param set-default CA_ROTOR0_KM 0.05
30+
param set-default CA_ROTOR1_PX -0.15
31+
param set-default CA_ROTOR1_PY -0.23
32+
param set-default CA_ROTOR1_KM 0.05
33+
param set-default CA_ROTOR2_PX 0.15
34+
param set-default CA_ROTOR2_PY -0.23
35+
param set-default CA_ROTOR2_KM -0.05
36+
param set-default CA_ROTOR3_PX -0.15
37+
param set-default CA_ROTOR3_PY 0.23
38+
param set-default CA_ROTOR3_KM -0.05
39+
40+
param set-default CA_SV_CS_COUNT 0
41+
42+
param set-default SIM_GZ_EC_FUNC1 101
43+
param set-default SIM_GZ_EC_FUNC2 102
44+
param set-default SIM_GZ_EC_FUNC3 103
45+
param set-default SIM_GZ_EC_FUNC4 104
46+
47+
param set-default SIM_GZ_EC_MIN1 10
48+
param set-default SIM_GZ_EC_MIN2 10
49+
param set-default SIM_GZ_EC_MIN3 10
50+
param set-default SIM_GZ_EC_MIN4 10
51+
52+
param set-default SIM_GZ_EC_MAX1 1500
53+
param set-default SIM_GZ_EC_MAX2 1500
54+
param set-default SIM_GZ_EC_MAX3 1500
55+
param set-default SIM_GZ_EC_MAX4 1500
56+
57+
param set-default FD_FAIL_R 70
58+
59+
param set-default FW_P_TC 0.6
60+
61+
param set-default FW_PR_I 0.3
62+
param set-default FW_PR_P 0.5
63+
param set-default FW_PSP_OFF 2
64+
param set-default FW_RR_FF 0.1
65+
param set-default FW_RR_I 0.1
66+
param set-default FW_RR_P 0.2
67+
param set-default FW_YR_FF 0 # make yaw rate controller very weak, only keep default P
68+
param set-default FW_YR_I 0
69+
param set-default FW_THR_TRIM 0.35
70+
param set-default FW_THR_MAX 0.8
71+
param set-default FW_THR_MIN 0.05
72+
param set-default FW_T_CLMB_MAX 6
73+
param set-default FW_T_HRATE_FF 0.5
74+
param set-default FW_T_SINK_MAX 3
75+
param set-default FW_T_SINK_MIN 1.6
76+
param set-default FW_AIRSPD_STALL 10
77+
param set-default FW_AIRSPD_MIN 14
78+
param set-default FW_AIRSPD_TRIM 18
79+
param set-default FW_AIRSPD_MAX 22
80+
81+
param set-default MC_AIRMODE 2
82+
param set-default MAN_ARM_GESTURE 0 # required for yaw airmode
83+
param set-default MC_ROLL_P 3
84+
param set-default MC_PITCH_P 3
85+
param set-default MC_ROLLRATE_P 0.3
86+
param set-default MC_PITCHRATE_P 0.3
87+
88+
param set-default VT_ARSP_TRANS 15
89+
param set-default VT_B_TRANS_DUR 5
90+
param set-default VT_FW_DIFTHR_EN 7
91+
param set-default VT_FW_DIFTHR_S_Y 1
92+
param set-default VT_F_TRANS_DUR 1.5
93+
param set-default VT_TYPE 0
94+
95+
param set-default WV_EN 0
96+
97+
param set-default EKF2_FUSE_BETA 0

ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -89,6 +89,7 @@ px4_add_romfs_files(
8989
4015_gz_r1_rover_mecanum
9090
4016_gz_x500_lidar_down
9191
4017_gz_x500_lidar_front
92+
4018_gz_quadtailsitter
9293

9394
6011_gazebo-classic_typhoon_h480
9495
6011_gazebo-classic_typhoon_h480.post

src/modules/simulation/gz_bridge/GZBridge.cpp

Lines changed: 6 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -226,17 +226,15 @@ int GZBridge::init()
226226
PX4_WARN("failed to subscribe to %s", lidar_sensor.c_str());
227227
}
228228

229-
#if 0
230229
// Airspeed: /world/$WORLD/model/$MODEL/link/airspeed_link/sensor/air_speed/air_speed
231-
std::string airpressure_topic = "/world/" + _world_name + "/model/" + _model_name +
232-
"/link/airspeed_link/sensor/air_speed/air_speed";
230+
std::string airspeed_topic = "/world/" + _world_name + "/model/" + _model_name +
231+
"/link/airspeed_link/sensor/air_speed/air_speed";
233232

234-
if (!_node.Subscribe(airpressure_topic, &GZBridge::airspeedCallback, this)) {
235-
PX4_ERR("failed to subscribe to %s", airpressure_topic.c_str());
233+
if (!_node.Subscribe(airspeed_topic, &GZBridge::airspeedCallback, this)) {
234+
PX4_ERR("failed to subscribe to %s", airspeed_topic.c_str());
236235
return PX4_ERROR;
237236
}
238237

239-
#endif
240238
// Air pressure: /world/$WORLD/model/$MODEL/link/base_link/sensor/air_pressure_sensor/air_pressure
241239
std::string air_pressure_topic = "/world/" + _world_name + "/model/" + _model_name +
242240
"/link/base_link/sensor/air_pressure_sensor/air_pressure";
@@ -449,8 +447,8 @@ void GZBridge::barometerCallback(const gz::msgs::FluidPressure &air_pressure)
449447
pthread_mutex_unlock(&_node_mutex);
450448
}
451449

452-
#if 0
453-
void GZBridge::airspeedCallback(const gz::msgs::AirSpeedSensor &air_speed)
450+
451+
void GZBridge::airspeedCallback(const gz::msgs::AirSpeed &air_speed)
454452
{
455453
if (hrt_absolute_time() == 0) {
456454
return;
@@ -475,7 +473,6 @@ void GZBridge::airspeedCallback(const gz::msgs::AirSpeedSensor &air_speed)
475473

476474
pthread_mutex_unlock(&_node_mutex);
477475
}
478-
#endif
479476

480477
void GZBridge::imuCallback(const gz::msgs::IMU &imu)
481478
{

src/modules/simulation/gz_bridge/GZBridge.hpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -68,6 +68,7 @@
6868

6969
#include <gz/msgs/imu.pb.h>
7070
#include <gz/msgs/fluid_pressure.pb.h>
71+
#include <gz/msgs/air_speed.pb.h>
7172
#include <gz/msgs/model.pb.h>
7273
#include <gz/msgs/odometry_with_covariance.pb.h>
7374
#include <gz/msgs/laserscan.pb.h>
@@ -106,7 +107,7 @@ class GZBridge : public ModuleBase<GZBridge>, public ModuleParams, public px4::S
106107

107108
void clockCallback(const gz::msgs::Clock &clock);
108109

109-
// void airspeedCallback(const gz::msgs::AirSpeedSensor &air_pressure);
110+
void airspeedCallback(const gz::msgs::AirSpeed &air_speed);
110111
void barometerCallback(const gz::msgs::FluidPressure &air_pressure);
111112
void imuCallback(const gz::msgs::IMU &imu);
112113
void poseInfoCallback(const gz::msgs::Pose_V &pose);
@@ -167,8 +168,8 @@ class GZBridge : public ModuleBase<GZBridge>, public ModuleParams, public px4::S
167168
// Subscriptions
168169
uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s};
169170

170-
//uORB::Publication<differential_pressure_s> _differential_pressure_pub{ORB_ID(differential_pressure)};
171171
uORB::Publication<distance_sensor_s> _distance_sensor_pub{ORB_ID(distance_sensor)};
172+
uORB::Publication<differential_pressure_s> _differential_pressure_pub{ORB_ID(differential_pressure)};
172173
uORB::Publication<obstacle_distance_s> _obstacle_distance_pub{ORB_ID(obstacle_distance)};
173174
uORB::Publication<vehicle_angular_velocity_s> _angular_velocity_ground_truth_pub{ORB_ID(vehicle_angular_velocity_groundtruth)};
174175
uORB::Publication<vehicle_attitude_s> _attitude_ground_truth_pub{ORB_ID(vehicle_attitude_groundtruth)};

0 commit comments

Comments
 (0)