Skip to content

Commit 0f55c7a

Browse files
authored
Merge branch 'main' into pr-fw-auto-trim
2 parents b47fc47 + 1c9c5e5 commit 0f55c7a

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

41 files changed

+393
-142
lines changed

ROMFS/px4fmu_common/init.d-posix/airframes/4009_gz_r1_rover

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -16,11 +16,12 @@ param set-default RD_WHEEL_TRACK 0.3
1616
param set-default RD_MAN_YAW_SCALE 0.1
1717
param set-default RD_MAX_ACCEL 6
1818
param set-default RD_MAX_JERK 30
19-
param set-default RD_MAX_SPEED 7
20-
param set-default RD_YAW_RATE_P 5
19+
param set-default RD_MAX_THR_YAW_R 5
20+
param set-default RD_YAW_RATE_P 0.1
2121
param set-default RD_YAW_RATE_I 0
2222
param set-default RD_YAW_P 5
2323
param set-default RD_YAW_I 0
24+
param set-default RD_MAX_THR_SPD 7
2425
param set-default RD_SPEED_P 1
2526
param set-default RD_SPEED_I 0
2627
param set-default RD_MAX_YAW_RATE 180

ROMFS/px4fmu_common/init.d/airframes/1102_tailsitter_duo_sih.hil

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -43,6 +43,10 @@ param set-default CA_SV_CS1_TRQ_P 0.3
4343
param set-default CA_SV_CS1_TRQ_Y -0.3
4444
param set-default CA_SV_CS1_TYPE 6
4545

46+
param set-default FW_AIRSPD_MAX 12
47+
param set-default FW_AIRSPD_MIN 7
48+
param set-default FW_AIRSPD_TRIM 10
49+
4650
param set-default HIL_ACT_FUNC1 101
4751
param set-default HIL_ACT_FUNC2 102
4852
param set-default HIL_ACT_FUNC5 202
@@ -62,6 +66,8 @@ param set-default CBRK_SUPPLY_CHK 894281
6266
# - without safety switch
6367
param set-default CBRK_IO_SAFETY 22027
6468

69+
param set-default SENS_DPRES_OFF 0.001
70+
6571
param set SIH_T_MAX 2.0
6672
param set SIH_Q_MAX 0.0165
6773
param set SIH_MASS 0.2
@@ -75,3 +81,5 @@ param set SIH_L_ROLL 0.145
7581

7682
# sih as tailsitter
7783
param set SIH_VEHICLE_TYPE 2
84+
85+
param set-default VT_ARSP_TRANS 6

ROMFS/px4fmu_common/init.d/airframes/50001_aion_robotics_r1_rover

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -25,12 +25,13 @@ param set-default RBCLW_REV 1 # reverse right wheels
2525
param set-default RD_WHEEL_TRACK 0.3
2626
param set-default RD_MAN_YAW_SCALE 1
2727
param set-default RD_MAX_ACCEL 5
28-
param set-default RD_MAX_JERK 50
29-
param set-default RD_MAX_SPEED 2
28+
param set-default RD_MAX_JERK 10
29+
param set-default RD_MAX_THR_YAW_R 4
3030
param set-default RD_YAW_RATE_P 0.1
3131
param set-default RD_YAW_RATE_I 0
3232
param set-default RD_YAW_P 5
3333
param set-default RD_YAW_I 0
34+
param set-default RD_MAX_THR_SPD 2
3435
param set-default RD_SPEED_P 0.5
3536
param set-default RD_SPEED_I 0.1
3637
param set-default RD_MAX_YAW_RATE 300

boards/cuav/x7pro/default.px4board

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -39,7 +39,6 @@ CONFIG_DRIVERS_TONE_ALARM=y
3939
CONFIG_DRIVERS_UAVCAN=y
4040
CONFIG_BOARD_UAVCAN_TIMER_OVERRIDE=2
4141
CONFIG_MODULES_AIRSPEED_SELECTOR=y
42-
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
4342
CONFIG_MODULES_BATTERY_STATUS=y
4443
CONFIG_MODULES_CAMERA_FEEDBACK=y
4544
CONFIG_MODULES_COMMANDER=y
@@ -70,7 +69,6 @@ CONFIG_MODULES_MC_POS_CONTROL=y
7069
CONFIG_MODULES_MC_RATE_CONTROL=y
7170
CONFIG_MODULES_NAVIGATOR=y
7271
CONFIG_MODULES_RC_UPDATE=y
73-
CONFIG_MODULES_ROVER_POS_CONTROL=y
7472
CONFIG_MODULES_SENSORS=y
7573
CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y
7674
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y

msg/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -74,6 +74,7 @@ set(msg_files
7474
DebugVect.msg
7575
DifferentialPressure.msg
7676
DistanceSensor.msg
77+
DistanceSensorModeChangeRequest.msg
7778
Ekf2Timestamps.msg
7879
EscReport.msg
7980
EscStatus.msg
Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,5 @@
1+
uint64 timestamp # time since system start (microseconds)
2+
3+
uint8 request_on_off # request to disable/enable the distance sensor
4+
uint8 REQUEST_OFF = 0
5+
uint8 REQUEST_ON = 1

msg/PositionSetpoint.msg

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -30,7 +30,8 @@ bool loiter_direction_counter_clockwise # loiter direction is clockwise by defau
3030
float32 loiter_orientation # Orientation of the major axis with respect to true north in rad [-pi,pi)
3131
uint8 loiter_pattern # loitern pattern to follow
3232

33-
float32 acceptance_radius # navigation acceptance_radius if we're doing waypoint navigation
33+
float32 acceptance_radius # horizontal acceptance_radius (meters)
34+
float32 alt_acceptance_radius # vertical acceptance radius, only used for fixed wing guidance, NAN = let guidance choose (meters)
3435

3536
float32 cruising_speed # the generally desired cruising speed (not a hard constraint)
3637
bool gliding_enabled # commands the vehicle to glide if the capability is available (fixed wing only)

msg/RoverDifferentialStatus.msg

Lines changed: 9 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -1,11 +1,13 @@
11
uint64 timestamp # time since system start (microseconds)
22

3-
float32 actual_speed # [m/s] Actual forward speed of the rover
4-
float32 actual_yaw_deg # [deg] Actual yaw of the rover
5-
float32 actual_yaw_rate_deg_s # [deg/s] Actual yaw rate of the rover
6-
float32 desired_yaw_rate_deg_s # [deg/s] Yaw rate setpoint for the closed loop yaw rate controller
7-
float32 pid_yaw_integral # Integral of the PID for the closed loop yaw controller
8-
float32 pid_yaw_rate_integral # Integral of the PID for the closed loop yaw rate controller
9-
float32 pid_throttle_integral # Integral of the PID for the closed loop speed controller
3+
float32 actual_speed # [m/s] Actual forward speed of the rover
4+
float32 actual_yaw # [rad] Actual yaw of the rover
5+
float32 actual_yaw_rate # [rad/s] Actual yaw rate of the rover
6+
float32 desired_yaw_rate # [rad/s] Yaw rate setpoint for the closed loop yaw rate controller
7+
float32 forward_speed_normalized # [-1, 1] Normalized forward speed setpoint
8+
float32 speed_diff_normalized # [-1, 1] Normalized speed difference setpoint between the left and right motor
9+
float32 pid_yaw_integral # Integral of the PID for the closed loop yaw controller
10+
float32 pid_yaw_rate_integral # Integral of the PID for the closed loop yaw rate controller
11+
float32 pid_throttle_integral # Integral of the PID for the closed loop speed controller
1012

1113
# TOPICS rover_differential_status

msg/TecsStatus.msg

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -27,3 +27,4 @@ float32 pitch_sp_rad # Current pitch setpoint [rad]
2727
float32 throttle_trim # estimated throttle value [0,1] required to fly level at equivalent_airspeed_sp in the current atmospheric conditions
2828

2929
float32 underspeed_ratio # 0: no underspeed, 1: maximal underspeed. Controller takes measures to avoid stall proportional to ratio if >0.
30+
float32 fast_descend_ratio # value indicating if fast descend mode is enabled with ramp up and ramp down [0-1]

src/drivers/distance_sensor/lightware_laser_i2c/lightware_laser_i2c.cpp

Lines changed: 15 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -55,6 +55,7 @@
5555
#include <uORB/Subscription.hpp>
5656
#include <uORB/topics/vehicle_status.h>
5757
#include <uORB/topics/parameter_update.h>
58+
#include <uORB/topics/distance_sensor_mode_change_request.h>
5859

5960
using namespace time_literals;
6061

@@ -143,6 +144,8 @@ class LightwareLaser : public device::I2C, public I2CSPIDriver<LightwareLaser>,
143144
uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)};
144145
uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)};
145146
typeof(px4::msg::VehicleStatus::vehicle_type) _vehicle_type{px4::msg::VehicleStatus::VEHICLE_TYPE_UNKNOWN};
147+
uORB::Subscription _dist_sense_mode_change_sub{ORB_ID(distance_sensor_mode_change_request)};
148+
typeof(px4::msg::DistanceSensorModeChangeRequest::request_on_off) _req_mode{px4::msg::DistanceSensorModeChangeRequest::REQUEST_OFF};
146149
bool _restriction{false};
147150
bool _auto_restriction{false};
148151
bool _prev_restriction{false};
@@ -412,6 +415,17 @@ void LightwareLaser::start()
412415

413416
int LightwareLaser::updateRestriction()
414417
{
418+
if (_dist_sense_mode_change_sub.updated()) {
419+
distance_sensor_mode_change_request_s dist_sense_mode_change;
420+
421+
if (_dist_sense_mode_change_sub.copy(&dist_sense_mode_change)) {
422+
_req_mode = dist_sense_mode_change.request_on_off;
423+
424+
} else {
425+
_req_mode = distance_sensor_mode_change_request_s::REQUEST_OFF;
426+
}
427+
}
428+
415429
px4::msg::VehicleStatus vehicle_status;
416430

417431
if (_vehicle_status_sub.update(&vehicle_status)) {
@@ -452,7 +466,7 @@ int LightwareLaser::updateRestriction()
452466
break;
453467

454468
case 2:
455-
_restriction = _auto_restriction;
469+
_restriction = _auto_restriction && _req_mode != distance_sensor_mode_change_request_s::REQUEST_ON;
456470
break;
457471
}
458472

0 commit comments

Comments
 (0)