mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-19 19:04:33 +08:00
Rename the invered state and make namespace more clear
- Addressing review comments
This commit is contained in:
committed by
Dennis Mannhart
parent
aac9221d95
commit
6938b7fe02
@@ -186,7 +186,7 @@ private:
|
||||
struct sensor_correction_s _sensor_correction {}; /**< sensor thermal corrections */
|
||||
struct sensor_bias_s _sensor_bias {}; /**< sensor in-run bias corrections */
|
||||
struct vehicle_land_detected_s _vehicle_land_detected {};
|
||||
struct landing_gear_s _landing_gear_state {};
|
||||
struct landing_gear_s _landing_gear {};
|
||||
|
||||
MultirotorMixer::saturation_status _saturation_status{};
|
||||
|
||||
|
||||
@@ -383,7 +383,7 @@ MulticopterAttitudeControl::landing_gear_state_poll()
|
||||
orb_check(_landing_gear_sub, &updated);
|
||||
|
||||
if (updated) {
|
||||
orb_copy(ORB_ID(landing_gear), _landing_gear_sub, &_landing_gear_state);
|
||||
orb_copy(ORB_ID(landing_gear), _landing_gear_sub, &_landing_gear);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -520,7 +520,7 @@ MulticopterAttitudeControl::generate_attitude_setpoint(float dt, bool reset_yaw_
|
||||
|
||||
attitude_setpoint.thrust_body[2] = -throttle_curve(_manual_control_sp.z);
|
||||
|
||||
_landing_gear_state.landing_gear = get_landing_gear_state();
|
||||
_landing_gear.landing_gear = get_landing_gear_state();
|
||||
|
||||
attitude_setpoint.timestamp = landing_gear.timestamp = hrt_absolute_time();
|
||||
orb_publish_auto(ORB_ID(vehicle_attitude_setpoint), &_vehicle_attitude_setpoint_pub, &attitude_setpoint, nullptr, ORB_PRIO_DEFAULT);
|
||||
@@ -773,7 +773,7 @@ MulticopterAttitudeControl::publish_actuator_controls()
|
||||
_actuators.control[1] = (PX4_ISFINITE(_att_control(1))) ? _att_control(1) : 0.0f;
|
||||
_actuators.control[2] = (PX4_ISFINITE(_att_control(2))) ? _att_control(2) : 0.0f;
|
||||
_actuators.control[3] = (PX4_ISFINITE(_thrust_sp)) ? _thrust_sp : 0.0f;
|
||||
_actuators.control[7] = (float)_landing_gear_state.landing_gear;
|
||||
_actuators.control[7] = (float)_landing_gear.landing_gear;
|
||||
_actuators.timestamp = hrt_absolute_time();
|
||||
_actuators.timestamp_sample = _sensor_gyro.timestamp;
|
||||
|
||||
@@ -819,7 +819,7 @@ MulticopterAttitudeControl::run()
|
||||
_sensor_correction_sub = orb_subscribe(ORB_ID(sensor_correction));
|
||||
_sensor_bias_sub = orb_subscribe(ORB_ID(sensor_bias));
|
||||
_vehicle_land_detected_sub = orb_subscribe(ORB_ID(vehicle_land_detected));
|
||||
_landing_gear_sub = orb_subscribe(ORB_ID(landing_gear));
|
||||
_landing_gear_sub = orb_subscribe(ORB_ID(landing_gear));
|
||||
|
||||
/* wakeup source: gyro data from sensor selected by the sensor app */
|
||||
px4_pollfd_struct_t poll_fds = {};
|
||||
|
||||
@@ -137,7 +137,7 @@ private:
|
||||
home_position_s _home_pos{}; /**< home position */
|
||||
vehicle_trajectory_waypoint_s _traj_wp_avoidance{}; /**< trajectory waypoint */
|
||||
vehicle_trajectory_waypoint_s _traj_wp_avoidance_desired{}; /**< desired waypoints, inputs to an obstacle avoidance module */
|
||||
landing_gear_s _landing_gear_state{};
|
||||
landing_gear_s _landing_gear{};
|
||||
|
||||
int8_t _old_landing_gear_position;
|
||||
|
||||
@@ -597,17 +597,6 @@ MulticopterPositionControl::run()
|
||||
parameters_update(true);
|
||||
poll_subscriptions();
|
||||
|
||||
// Let's be safe and have the landing gear down by default
|
||||
_landing_gear_state.landing_gear = landing_gear_s::LANDING_GEAR_DOWN;
|
||||
_landing_gear_state.timestamp = hrt_absolute_time();
|
||||
|
||||
if (_landing_gear_pub != nullptr) {
|
||||
orb_publish(ORB_ID(landing_gear), _landing_gear_pub, &_landing_gear_state);
|
||||
|
||||
} else {
|
||||
_landing_gear_pub = orb_advertise(ORB_ID(landing_gear), &_landing_gear_state);
|
||||
}
|
||||
|
||||
// setup file descriptor to poll the local position as loop wakeup source
|
||||
px4_pollfd_struct_t poll_fd = {.fd = _local_pos_sub};
|
||||
poll_fd.events = POLLIN;
|
||||
@@ -816,14 +805,14 @@ MulticopterPositionControl::run()
|
||||
if (_old_landing_gear_position != constraints.landing_gear
|
||||
&& constraints.landing_gear != vehicle_constraints_s::GEAR_KEEP) {
|
||||
|
||||
_landing_gear_state.landing_gear = constraints.landing_gear;
|
||||
_landing_gear_state.timestamp = hrt_absolute_time();
|
||||
_landing_gear.landing_gear = constraints.landing_gear;
|
||||
_landing_gear.timestamp = hrt_absolute_time();
|
||||
|
||||
if (_landing_gear_pub != nullptr) {
|
||||
orb_publish(ORB_ID(landing_gear), _landing_gear_pub, &_landing_gear_state);
|
||||
orb_publish(ORB_ID(landing_gear), _landing_gear_pub, &_landing_gear);
|
||||
|
||||
} else {
|
||||
_landing_gear_pub = orb_advertise(ORB_ID(landing_gear), &_landing_gear_state);
|
||||
_landing_gear_pub = orb_advertise(ORB_ID(landing_gear), &_landing_gear);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
Reference in New Issue
Block a user