Skip to content

Commit

Permalink
Revert "Update GZBridge to be able to use gazebo airspeed. Add quadta…
Browse files Browse the repository at this point in the history
…ilsitter. (#23455)" (#23583)

This reverts commit 7e45f49.

Co-authored-by: jmackay2 <[email protected]>
  • Loading branch information
Jaeyoung-Lim and jmackay2 authored Aug 20, 2024
1 parent 0931179 commit f252e20
Show file tree
Hide file tree
Showing 7 changed files with 16 additions and 103 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ param set-default PWM_MAIN_FUNC3 103
param set-default PWM_MAIN_FUNC4 104
param set-default PWM_MAIN_FUNC5 0

param set-default FD_FAIL_R 70
parm set-default FD_FAIL_R 70

param set-default FW_P_TC 0.6

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,9 @@ PX4_SIM_MODEL=${PX4_SIM_MODEL:=standard_vtol}
param set-default SIM_GZ_EN 1

param set-default SENS_EN_GPSSIM 1
param set-default SENS_EN_BAROSIM 0
param set-default SENS_EN_MAGSIM 1
param set-default SENS_EN_ARSPDSIM 1

# TODO: Enable motor failure detection when the
# VTOL no longer reports 0A for all ESCs in SITL
Expand Down
92 changes: 0 additions & 92 deletions ROMFS/px4fmu_common/init.d-posix/airframes/4014_gz_quadtailsitter

This file was deleted.

1 change: 0 additions & 1 deletion ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -85,7 +85,6 @@ px4_add_romfs_files(
4011_gz_lawnmower
4012_gz_rover_ackermann
4013_gz_x500_lidar
4014_gz_quadtailsitter

6011_gazebo-classic_typhoon_h480
6011_gazebo-classic_typhoon_h480.post
Expand Down
16 changes: 10 additions & 6 deletions src/modules/simulation/gz_bridge/GZBridge.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -203,15 +203,17 @@ int GZBridge::init()
PX4_WARN("failed to subscribe to %s", laser_scan_topic.c_str());
}

// Airspeed: /world/$WORLD/model/$MODEL/link/base_link/sensor/airspeed_sensor/air_speed
std::string airspeed_topic = "/world/" + _world_name + "/model/" + _model_name +
"/link/base_link/sensor/airspeed_sensor/air_speed";
#if 0
// Airspeed: /world/$WORLD/model/$MODEL/link/airspeed_link/sensor/air_speed/air_speed
std::string airpressure_topic = "/world/" + _world_name + "/model/" + _model_name +
"/link/airspeed_link/sensor/air_speed/air_speed";

if (!_node.Subscribe(airspeed_topic, &GZBridge::airspeedCallback, this)) {
PX4_ERR("failed to subscribe to %s", airspeed_topic.c_str());
if (!_node.Subscribe(airpressure_topic, &GZBridge::airspeedCallback, this)) {
PX4_ERR("failed to subscribe to %s", airpressure_topic.c_str());
return PX4_ERROR;
}

#endif
// Air pressure: /world/$WORLD/model/$MODEL/link/base_link/sensor/air_pressure_sensor/air_pressure
std::string air_pressure_topic = "/world/" + _world_name + "/model/" + _model_name +
"/link/base_link/sensor/air_pressure_sensor/air_pressure";
Expand Down Expand Up @@ -424,7 +426,8 @@ void GZBridge::barometerCallback(const gz::msgs::FluidPressure &air_pressure)
pthread_mutex_unlock(&_node_mutex);
}

void GZBridge::airspeedCallback(const gz::msgs::AirSpeed &air_speed)
#if 0
void GZBridge::airspeedCallback(const gz::msgs::AirSpeedSensor &air_speed)
{
if (hrt_absolute_time() == 0) {
return;
Expand All @@ -449,6 +452,7 @@ void GZBridge::airspeedCallback(const gz::msgs::AirSpeed &air_speed)

pthread_mutex_unlock(&_node_mutex);
}
#endif

void GZBridge::imuCallback(const gz::msgs::IMU &imu)
{
Expand Down
4 changes: 2 additions & 2 deletions src/modules/simulation/gz_bridge/GZBridge.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -102,7 +102,7 @@ class GZBridge : public ModuleBase<GZBridge>, public ModuleParams, public px4::S

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

void airspeedCallback(const gz::msgs::AirSpeed &air_speed);
// void airspeedCallback(const gz::msgs::AirSpeedSensor &air_pressure);
void barometerCallback(const gz::msgs::FluidPressure &air_pressure);
void imuCallback(const gz::msgs::IMU &imu);
void poseInfoCallback(const gz::msgs::Pose_V &pose);
Expand All @@ -123,7 +123,7 @@ class GZBridge : public ModuleBase<GZBridge>, public ModuleParams, public px4::S
// Subscriptions
uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s};

uORB::Publication<differential_pressure_s> _differential_pressure_pub{ORB_ID(differential_pressure)};
//uORB::Publication<differential_pressure_s> _differential_pressure_pub{ORB_ID(differential_pressure)};
uORB::Publication<obstacle_distance_s> _obstacle_distance_pub{ORB_ID(obstacle_distance)};
uORB::Publication<vehicle_angular_velocity_s> _angular_velocity_ground_truth_pub{ORB_ID(vehicle_angular_velocity_groundtruth)};
uORB::Publication<vehicle_attitude_s> _attitude_ground_truth_pub{ORB_ID(vehicle_attitude_groundtruth)};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -195,7 +195,7 @@ int SensorAirspeedSim::print_usage(const char *reason)
)DESCR_STR");

PRINT_MODULE_USAGE_NAME("sensor_airspeed_sim", "system");
PRINT_MODULE_USAGE_NAME("sensor_arispeed_sim", "system");
PRINT_MODULE_USAGE_COMMAND("start");
PRINT_MODULE_USAGE_DEFAULT_COMMANDS();

Expand Down

0 comments on commit f252e20

Please sign in to comment.