From 0c8e31ea7d49f29202ce4a247a303cee830ed728 Mon Sep 17 00:00:00 2001 From: haitomatic Date: Fri, 20 Oct 2023 12:13:22 +0000 Subject: [PATCH] simulation: gz bridge refactor rover pos control: velocity control refactor --- .../init.d-posix/airframes/4401_gz_ssrc_fog_x | 25 ++++--- .../airframes/4430_gz_ssrc_striver_mini | 1 + .../airframes/4440_gz_ssrc_skywalker_x8 | 1 + .../airframes/50005_gz_ssrc_scout_mini_rover | 11 ++- packaging/entrypoint_sitl_gzsim.sh | 11 +-- .../RoverPositionControl.cpp | 44 ++++++++--- .../RoverPositionControl.hpp | 10 ++- .../rover_pos_control_params.c | 62 ++++++++++++++++ src/modules/simulation/gz_bridge/GZBridge.cpp | 73 +++++++++---------- src/modules/simulation/gz_bridge/GZBridge.hpp | 19 +++-- src/modules/simulation/gz_bridge/parameters.c | 11 ++- 11 files changed, 189 insertions(+), 79 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/4401_gz_ssrc_fog_x b/ROMFS/px4fmu_common/init.d-posix/airframes/4401_gz_ssrc_fog_x index 5b014bdad352..708253259623 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/4401_gz_ssrc_fog_x +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/4401_gz_ssrc_fog_x @@ -12,6 +12,7 @@ PX4_GZ_WORLD=${PX4_GZ_WORLD:=default} PX4_SIM_MODEL=${PX4_SIM_MODEL:=holybro-x500} param set-default SIM_GZ_EN 1 +param set-default SIM_GZ_RUN_GZSIM 0 param set-default SENS_EN_GPSSIM 1 param set-default SENS_EN_BAROSIM 1 @@ -36,20 +37,20 @@ param set-default CA_ROTOR3_PX -0.175 param set-default CA_ROTOR3_PY 0.175 param set-default CA_ROTOR3_KM -0.05 -param set-default SIM_GZ_FUNC1 101 -param set-default SIM_GZ_FUNC2 102 -param set-default SIM_GZ_FUNC3 103 -param set-default SIM_GZ_FUNC4 104 +param set-default SIM_GZ_EC_FUNC1 101 +param set-default SIM_GZ_EC_FUNC2 102 +param set-default SIM_GZ_EC_FUNC3 103 +param set-default SIM_GZ_EC_FUNC4 104 -param set-default SIM_GZ_MIN1 150 -param set-default SIM_GZ_MIN2 150 -param set-default SIM_GZ_MIN3 150 -param set-default SIM_GZ_MIN4 150 +param set-default SIM_GZ_EC_MIN1 150 +param set-default SIM_GZ_EC_MIN2 150 +param set-default SIM_GZ_EC_MIN3 150 +param set-default SIM_GZ_EC_MIN4 150 -param set-default SIM_GZ_MAX1 1000 -param set-default SIM_GZ_MAX2 1000 -param set-default SIM_GZ_MAX3 1000 -param set-default SIM_GZ_MAX4 1000 +param set-default SIM_GZ_EC_MAX1 1000 +param set-default SIM_GZ_EC_MAX2 1000 +param set-default SIM_GZ_EC_MAX3 1000 +param set-default SIM_GZ_EC_MAX4 1000 param set-default MPC_THR_HOVER 0.60 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/4430_gz_ssrc_striver_mini b/ROMFS/px4fmu_common/init.d-posix/airframes/4430_gz_ssrc_striver_mini index 7484028ff7d2..227970ad3c04 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/4430_gz_ssrc_striver_mini +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/4430_gz_ssrc_striver_mini @@ -13,6 +13,7 @@ PX4_GZ_WORLD=${PX4_GZ_WORLD:=default} PX4_SIM_MODEL=${PX4_SIM_MODEL:=striver_mini} param set-default SIM_GZ_EN 1 +param set-default SIM_GZ_RUN_GZSIM 0 # Control allocator parameters param set-default CA_AIRFRAME 2 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/4440_gz_ssrc_skywalker_x8 b/ROMFS/px4fmu_common/init.d-posix/airframes/4440_gz_ssrc_skywalker_x8 index ecb60a69618d..6d3a6f525a8c 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/4440_gz_ssrc_skywalker_x8 +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/4440_gz_ssrc_skywalker_x8 @@ -13,6 +13,7 @@ PX4_GZ_WORLD=${PX4_GZ_WORLD:=default} PX4_SIM_MODEL=${PX4_SIM_MODEL:=skywalker_x8} param set-default SIM_GZ_EN 1 +param set-default SIM_GZ_RUN_GZSIM 0 # Control allocator parameters param set-default CA_AIRFRAME 1 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/50005_gz_ssrc_scout_mini_rover b/ROMFS/px4fmu_common/init.d-posix/airframes/50005_gz_ssrc_scout_mini_rover index 1a441448594c..c44cb066fb4c 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/50005_gz_ssrc_scout_mini_rover +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/50005_gz_ssrc_scout_mini_rover @@ -15,6 +15,7 @@ PX4_GZ_WORLD=${PX4_GZ_WORLD:=default} PX4_SIM_MODEL=${PX4_SIM_MODEL:=scout_mini} param set-default SIM_GZ_EN 1 +param set-default SIM_GZ_RUN_GZSIM 0 param set-default CA_AIRFRAME 6 @@ -67,6 +68,10 @@ param set-default GND_THR_MIN 0 param set-default GND_SPEED_P 0.4 param set-default GND_SPEED_I 1 param set-default GND_SPEED_D 0.001 -param set-default GND_SPEED_IMAX 1 -param set-default GND_SPEED_MAX 1 -param set-default GND_SPEED_THR_SC 1 +param set-default GND_SPEED_MAX 3.0 +param set-default GND_SPEED_TRIM 3.0 +param set-default GND_SPEED_THR_SC 1.0 +param set-default GND_VEL_CTRL 1 +param set-default GND_ANG_VEL_CTRL 1 +param set-default GND_ACC_LIMIT 10 +param set-default GND_DEC_LIMIT 100 diff --git a/packaging/entrypoint_sitl_gzsim.sh b/packaging/entrypoint_sitl_gzsim.sh index a13919f04d48..ace9a173475c 100755 --- a/packaging/entrypoint_sitl_gzsim.sh +++ b/packaging/entrypoint_sitl_gzsim.sh @@ -6,18 +6,19 @@ export PATH=/px4_sitl/bin:$PATH case $PX4_VEHICLE_TYPE in mc) export PX4_SYS_AUTOSTART=4401 + export PX4_GZ_MODEL=holybro-x500 ;; rover) - export PX4_SYS_AUTOSTART=50006 + export PX4_SYS_AUTOSTART=50005 + export PX4_GZ_MODEL=scout_mini ;; vtol) export PX4_SYS_AUTOSTART=4430 + export PX4_GZ_MODEL=striver_mini ;; fw) export PX4_SYS_AUTOSTART=4440 - ;; - uuv) - export PX4_SYS_AUTOSTART=4403 + export PX4_GZ_MODEL=skywalker_x8 ;; *) echo "ERROR: unknown vehicle type: $PX4_VEHICLE_TYPE" @@ -33,4 +34,4 @@ export GZ_IP=$(hostname -i) source /opt/ros/humble/setup.sh -/px4/bin/px4 -d -s /px4/etc/init.d-posix/rcS -w /px4 +/px4_sitl/bin/px4 -d -s /px4_sitl/etc/init.d-posix/rcS -w /px4_sitl diff --git a/src/modules/rover_pos_control/RoverPositionControl.cpp b/src/modules/rover_pos_control/RoverPositionControl.cpp index 24909280e99c..bff05a28a72e 100644 --- a/src/modules/rover_pos_control/RoverPositionControl.cpp +++ b/src/modules/rover_pos_control/RoverPositionControl.cpp @@ -320,20 +320,38 @@ RoverPositionControl::control_velocity(const matrix::Vector3f ¤t_velocity) const Vector3f desired_velocity{_trajectory_setpoint.velocity}; float dt = 0.01; // Using non zero value to a avoid division by zero + if (_control_velocity_last_called > 0) { + dt = hrt_elapsed_time(&_control_velocity_last_called) * 1e-6f; + } + + _control_velocity_last_called = hrt_absolute_time(); + const float mission_throttle = _param_throttle_cruise.get(); const float desired_speed = desired_velocity.norm(); + float desired_angular_vel = PX4_ISFINITE(_trajectory_setpoint.yawspeed) ? _trajectory_setpoint.yawspeed : desired_velocity(1); - if (desired_speed > 0.01f) { + if (desired_speed > 0.01f || desired_angular_vel > 0.01f) { const Dcmf R_to_body(Quatf(_vehicle_att.q).inversed()); const Vector3f vel = R_to_body * Vector3f(current_velocity(0), current_velocity(1), current_velocity(2)); const float x_vel = vel(0); const float x_acc = _vehicle_acceleration_sub.get().xyz[0]; - - const float control_throttle = pid_calculate(&_speed_ctrl, desired_speed, x_vel, x_acc, dt); - - //Constrain maximum throttle to mission throttle - _throttle_control = math::constrain(control_throttle, 0.0f, mission_throttle); + float control_throttle = 0.0f; + const float speed_error = desired_speed - x_vel; + + if (_param_speed_control_mode.get() == 0) { + // Use PID control + control_throttle = pid_calculate(&_speed_ctrl, desired_speed, x_vel, x_acc, dt); + _throttle_control = math::constrain(control_throttle, 0.0f, mission_throttle); + } else if (_param_speed_control_mode.get() == 1) { + // Use acc limited direct control + float max_delta_speed = (speed_error > 0 ? _param_speed_acc_limit.get() : _param_speed_dec_limit.get()) * dt; + // Compute the velocity with delta speed and constrain it to GND_SPEED_TRIM + float command_velocity = math::constrain(x_vel + math::constrain(speed_error, -max_delta_speed, max_delta_speed), + -_param_gndspeed_trim.get(), _param_gndspeed_trim.get()); + // Compute the desired velocity and divide it by max speed to get the throttle control + _throttle_control = command_velocity / _param_gndspeed_max.get(); + } Vector3f desired_body_velocity; @@ -345,11 +363,15 @@ RoverPositionControl::control_velocity(const matrix::Vector3f ¤t_velocity) desired_body_velocity = R_to_body * desired_velocity; } - const float desired_theta = atan2f(desired_body_velocity(1), desired_body_velocity(0)); - float control_effort = desired_theta / _param_max_turn_angle.get(); - control_effort = math::constrain(control_effort, -1.0f, 1.0f); - - _yaw_control = control_effort; + if (_param_ang_vel_control_mode.get() == 0) { + // Determine yaw from XY vector + const float desired_theta = atan2f(desired_body_velocity(1), desired_body_velocity(0)); + _yaw_control = math::constrain(desired_theta / _param_max_turn_angle.get(), -1.0f, 1.0f); + } else if (_param_ang_vel_control_mode.get() == 1) { + // Use direct yaw input from velocity setpoint + // Limit it to max anguler velocity + _yaw_control = math::constrain(desired_angular_vel, -_param_max_angular_velocity.get(), _param_max_angular_velocity.get()); + } } else { diff --git a/src/modules/rover_pos_control/RoverPositionControl.hpp b/src/modules/rover_pos_control/RoverPositionControl.hpp index ee1c65efa03d..851289365263 100644 --- a/src/modules/rover_pos_control/RoverPositionControl.hpp +++ b/src/modules/rover_pos_control/RoverPositionControl.hpp @@ -133,6 +133,7 @@ class RoverPositionControl final : public ModuleBase, publ perf_counter_t _loop_perf; /**< loop performance counter */ hrt_abstime _control_position_last_called{0}; /**, publ float _manual_yaw_sp{0.0}; bool _reset_yaw_sp{true}; - float _throttle_control{0.f}; - float _yaw_control{0.f}; + float _throttle_control{0.0}; + float _yaw_control{0.0}; DEFINE_PARAMETERS( (ParamFloat) _param_l1_period, @@ -179,6 +180,8 @@ class RoverPositionControl final : public ModuleBase, publ (ParamFloat) _param_gndspeed_max, (ParamInt) _param_speed_control_mode, + (ParamInt) _param_vel_control_mode, + (ParamInt) _param_ang_vel_control_mode, (ParamFloat) _param_speed_p, (ParamFloat) _param_speed_i, (ParamFloat) _param_speed_d, @@ -190,7 +193,10 @@ class RoverPositionControl final : public ModuleBase, publ (ParamFloat) _param_throttle_cruise, (ParamFloat) _param_wheel_base, + (ParamFloat) _param_speed_acc_limit, + (ParamFloat) _param_speed_dec_limit, (ParamFloat) _param_max_turn_angle, + (ParamFloat) _param_max_angular_velocity, (ParamFloat) _param_gnd_man_y_max, (ParamFloat) _param_nav_loiter_rad /**< loiter radius for Rover */ ) diff --git a/src/modules/rover_pos_control/rover_pos_control_params.c b/src/modules/rover_pos_control/rover_pos_control_params.c index 6458fb1fea65..7106cc46b09c 100644 --- a/src/modules/rover_pos_control/rover_pos_control_params.c +++ b/src/modules/rover_pos_control/rover_pos_control_params.c @@ -164,6 +164,32 @@ PARAM_DEFINE_FLOAT(GND_THR_MIN, 0.0f); */ PARAM_DEFINE_INT32(GND_SP_CTRL_MODE, 1); +/** + * Control mode for speed + * + * This allows the user to choose between PID control or direct throttle control to work with + * rover_interface + * @min 0 + * @max 1 + * @value 0 PID control + * @value 1 Direct control + * @group Rover Position Control + */ +PARAM_DEFINE_INT32(GND_VEL_CTRL, 0); + +/** + * Control mode for angular velocity + * + * Whether the angular velocity will be done with XY vel command difference, or the angular + * velocity commands are given directly either in yawspeed or _trajectory_setpoint.velocity(1) + * @min 0 + * @max 1 + * @value 0 Difference in XY vel commands + * @value 1 Raw input from controller + * @group Rover Position Control + */ +PARAM_DEFINE_INT32(GND_ANG_VEL_CTRL, 0); + /** * Speed proportional gain * @@ -260,6 +286,42 @@ PARAM_DEFINE_FLOAT(GND_SPEED_TRIM, 3.0f); */ PARAM_DEFINE_FLOAT(GND_SPEED_MAX, 10.0f); +/** + * Velocity control acceleration limit + * + * @unit m/s^2 + * @min 0.01 + * @max 100.0 + * @decimal 2 + * @increment 0.05 + * @group Rover Position Control + */ +PARAM_DEFINE_FLOAT(GND_ACC_LIMIT, 1.0f); + +/** + * Velocity control deceleration limit + * + * @unit m/s^2 + * @min 0.005 + * @max 100.0 + * @decimal 2 + * @increment 0.05 + * @group Rover Position Control + */ +PARAM_DEFINE_FLOAT(GND_DEC_LIMIT, 1.0f); + +/** + * Limit the given angular velocity + * + * @unit rad/s + * @min 0.0 + * @max 3.14159 + * @decimal 3 + * @increment 0.01 + * @group Rover Position Control + */ +PARAM_DEFINE_FLOAT(GND_MAX_ANG_VEL, 0.4f); + /** * Maximum turn angle for Ackerman steering. * diff --git a/src/modules/simulation/gz_bridge/GZBridge.cpp b/src/modules/simulation/gz_bridge/GZBridge.cpp index 5f57ad09f45f..6bfbee43dcdc 100644 --- a/src/modules/simulation/gz_bridge/GZBridge.cpp +++ b/src/modules/simulation/gz_bridge/GZBridge.cpp @@ -45,19 +45,25 @@ #include #include -GZBridge::GZBridge(const char *world, const char *name, const char *model, - const char *type, const char *pose_str) : +GZBridge::GZBridge(const char *world, const char *name, const char *model, const char *pose_str) : ModuleParams(nullptr), ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::rate_ctrl), _world_name(world), _model_name(name), _model_sim(model), - _vehicle_type(type), _model_pose(pose_str) { pthread_mutex_init(&_node_mutex, nullptr); updateParams(); + + // get current simulated vehicle airframe type + param_get(param_find("CA_AIRFRAME"), &_airframe); + + // get rover max speed + if (_airframe == 6) { + param_get(param_find("GND_SPEED_MAX"), &_rover_max_speed); + } } GZBridge::~GZBridge() @@ -163,18 +169,6 @@ int GZBridge::init() return PX4_ERROR; } - // output (rover vehicle type) eg /model/$MODEL_NAME/cmd_vel - if (_vehicle_type == "rover") { - std::string cmd_vel_topic = "/model/" + _model_name + "/cmd_vel"; - _cmd_vel_pub = _node.Advertise(cmd_vel_topic); - - if (!_cmd_vel_pub.Valid()) { - PX4_ERR("failed to advertise %s", cmd_vel_topic.c_str()); - return PX4_ERROR; - } - - } - #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 + @@ -205,6 +199,17 @@ int GZBridge::init() return PX4_ERROR; } + // output (rover airframe type) eg /model/$MODEL_NAME/cmd_vel + if (_airframe == 6) { + std::string cmd_vel_topic = "/model/" + _model_name + "/cmd_vel"; + _cmd_vel_pub = _node.Advertise(cmd_vel_topic); + + if (!_cmd_vel_pub.Valid()) { + PX4_ERR("failed to advertise %s", cmd_vel_topic.c_str()); + return PX4_ERROR; + } + } + ScheduleNow(); return OK; } @@ -215,7 +220,6 @@ int GZBridge::task_spawn(int argc, char *argv[]) const char *model_name = nullptr; const char *model_pose = nullptr; const char *model_sim = nullptr; - const char *vehicle_type = nullptr; const char *px4_instance = nullptr; std::string model_name_std; @@ -252,11 +256,6 @@ int GZBridge::task_spawn(int argc, char *argv[]) px4_instance = myoptarg; break; - case 'v': - // vehicle type - vehicle_type = myoptarg; - break; - case '?': error_flag = true; break; @@ -280,10 +279,6 @@ int GZBridge::task_spawn(int argc, char *argv[]) model_sim = ""; } - if (!vehicle_type) { - vehicle_type = "mc"; - } - if (!px4_instance) { if (!model_name) { model_name = model_sim; @@ -294,10 +289,9 @@ int GZBridge::task_spawn(int argc, char *argv[]) model_name = model_name_std.c_str(); } - PX4_INFO("world: %s, model name: %s, simulation model: %s, vehicle type: %s", world_name, model_name, model_sim, - vehicle_type); + PX4_INFO("world: %s, model name: %s, simulation model: %s", world_name, model_name, model_sim); - GZBridge *instance = new GZBridge(world_name, model_name, model_sim, vehicle_type, model_pose); + GZBridge *instance = new GZBridge(world_name, model_name, model_sim, model_pose); if (instance) { _object.store(instance); @@ -692,13 +686,15 @@ void GZBridge::odometryCallback(const gz::msgs::OdometryWithCovariance &odometry void GZBridge::updateCmdVel() { bool do_update = false; + float rover_throttle_control = 0.0f; + float rover_yaw_control = 0.0f; // Check torque setppoint update if (_vehicle_torque_setpoint_sub.updated()) { vehicle_torque_setpoint_s vehicle_torque_setpoint_msg; if (_vehicle_torque_setpoint_sub.copy(&vehicle_torque_setpoint_msg)) { - _rover_yaw_control = vehicle_torque_setpoint_msg.xyz[2]; + rover_yaw_control = vehicle_torque_setpoint_msg.xyz[2]; do_update = true; } } @@ -708,19 +704,21 @@ void GZBridge::updateCmdVel() vehicle_thrust_setpoint_s vehicle_thrust_setpoint_msg; if (_vehicle_thrust_setpoint_sub.copy(&vehicle_thrust_setpoint_msg)) { - _rover_throttle_control = vehicle_thrust_setpoint_msg.xyz[0]; + /** + * On physical rover the max speed scale back is only for mission mode + * But here, we simplify the logic and apply the scale back for both + * manual and mission mode + */ + rover_throttle_control = vehicle_thrust_setpoint_msg.xyz[0] * _rover_max_speed; do_update = true; } } if (do_update) { - auto throttle = 1.0f * _rover_throttle_control; - auto steering = _rover_yaw_control; - // publish cmd_vel gz::msgs::Twist cmd_vel_message; - cmd_vel_message.mutable_linear()->set_x(throttle); - cmd_vel_message.mutable_angular()->set_z(steering); + cmd_vel_message.mutable_linear()->set_x(rover_throttle_control); + cmd_vel_message.mutable_angular()->set_z(rover_yaw_control); if (_cmd_vel_pub.Valid()) { _cmd_vel_pub.Publish(cmd_vel_message); @@ -728,7 +726,6 @@ void GZBridge::updateCmdVel() } } - void GZBridge::rotateQuaternion(gz::math::Quaterniond &q_FRD_to_NED, const gz::math::Quaterniond q_FLU_to_ENU) { // FLU (ROS) to FRD (PX4) static rotation @@ -771,8 +768,8 @@ void GZBridge::Run() _mixing_interface_servo.updateParams(); } - // In case of rover vehicle type, publish gz cmd_vel - if (_vehicle_type == "rover") { updateCmdVel(); } + // In case of differential drive rover airframe type, publish gz cmd_vel + if (_airframe == 6) { updateCmdVel(); } ScheduleDelayed(10_ms); diff --git a/src/modules/simulation/gz_bridge/GZBridge.hpp b/src/modules/simulation/gz_bridge/GZBridge.hpp index fad051dc8853..0ed1ca3e4f9c 100644 --- a/src/modules/simulation/gz_bridge/GZBridge.hpp +++ b/src/modules/simulation/gz_bridge/GZBridge.hpp @@ -72,7 +72,7 @@ using namespace time_literals; class GZBridge : public ModuleBase, public ModuleParams, public px4::ScheduledWorkItem { public: - GZBridge(const char *world, const char *name, const char *model, const char *type, const char *pose_str); + GZBridge(const char *world, const char *name, const char *model, const char *pose_str); ~GZBridge() override; /** @see ModuleBase */ @@ -97,6 +97,12 @@ class GZBridge : public ModuleBase, public ModuleParams, public px4::S bool updateClock(const uint64_t tv_sec, const uint64_t tv_nsec); + /** + * In case of rover: listen to vehicle thrust and torque setpoint and + * publish to simulated rover cmd_vel + */ + void updateCmdVel(); + void clockCallback(const gz::msgs::Clock &clock); // void airspeedCallback(const gz::msgs::AirSpeedSensor &air_pressure); @@ -104,7 +110,6 @@ class GZBridge : public ModuleBase, public ModuleParams, public px4::S void imuCallback(const gz::msgs::IMU &imu); void poseInfoCallback(const gz::msgs::Pose_V &pose); void odometryCallback(const gz::msgs::OdometryWithCovariance &odometry); - void updateCmdVel(); /** * @@ -150,18 +155,18 @@ class GZBridge : public ModuleBase, public ModuleParams, public px4::S const std::string _world_name; const std::string _model_name; const std::string _model_sim; - const std::string _vehicle_type; const std::string _model_pose; - float _temperature{288.15}; // 15 degrees + int32_t _airframe; - float _rover_throttle_control{0.0f}; + float _rover_max_speed{0.0}; - float _rover_yaw_control{0.0f}; + float _temperature{288.15}; // 15 degrees - gz::transport::Node _node; gz::transport::Node::Publisher _cmd_vel_pub; + gz::transport::Node _node; + DEFINE_PARAMETERS( (ParamFloat) _param_sim_home_lat, (ParamFloat) _param_sim_home_lon, diff --git a/src/modules/simulation/gz_bridge/parameters.c b/src/modules/simulation/gz_bridge/parameters.c index 513c67436cef..8f4a81eec170 100644 --- a/src/modules/simulation/gz_bridge/parameters.c +++ b/src/modules/simulation/gz_bridge/parameters.c @@ -36,10 +36,19 @@ * * @boolean * @reboot_required true - * @group UAVCAN + * @group Simulator */ PARAM_DEFINE_INT32(SIM_GZ_EN, 0); +/** + * Simulator Gazebo run enable + * + * @boolean + * @reboot_required true + * @group Simulator + */ +PARAM_DEFINE_INT32(SIM_GZ_RUN_GZSIM, 1); + /** * simulator origin latitude *