Skip to content

Commit 4ec9990

Browse files
committed
Send angles in actual range instead of hardcoded angles
1 parent ebcb99d commit 4ec9990

File tree

6 files changed

+22
-16
lines changed

6 files changed

+22
-16
lines changed

ROMFS/px4fmu_common/init.d-posix/airframes/4011_gz_lawnmower

+6-6
Original file line numberDiff line numberDiff line change
@@ -62,17 +62,17 @@ param set-default SIM_GZ_WH_REV 0 # no need to reverse any wheels
6262

6363
# Cutter deck blades clutch, PCA9685 servo channel 3, "RC FLAPS" (406) - leftmost switch, or "Servo 3" (203):
6464
param set-default SIM_GZ_SV_FUNC3 203
65-
param set-default SIM_GZ_SV_MIN3 0
66-
param set-default SIM_GZ_SV_MAX3 1000
67-
param set-default SIM_GZ_SV_DIS3 500
65+
param set-default SIM_GZ_SV_MIN3 900
66+
param set-default SIM_GZ_SV_MAX3 2700
67+
param set-default SIM_GZ_SV_DIS3 1800
6868
param set-default SIM_GZ_SV_FAIL3 500
6969

7070
# Gas engine throttle, PCA9685 servo channel 4, "RC AUX1" (407) - left knob, or "Servo 4" (204):
7171
# - on minimum when disarmed or failed:
7272
param set-default SIM_GZ_SV_FUNC4 204
73-
param set-default SIM_GZ_SV_MIN4 0
74-
param set-default SIM_GZ_SV_MAX4 1000
75-
param set-default SIM_GZ_SV_DIS4 500
73+
param set-default SIM_GZ_SV_MIN4 900
74+
param set-default SIM_GZ_SV_MAX4 2700
75+
param set-default SIM_GZ_SV_DIS4 1800
7676
param set-default SIM_GZ_SV_FAIL4 500
7777

7878
# Controlling PCA9685 servos 5,6,7,8 directly via "Servo 5..8" setting, by publishing actuator_servos.control[]:

ROMFS/px4fmu_common/init.d-posix/airframes/4012_gz_rover_ackermann

+2
Original file line numberDiff line numberDiff line change
@@ -49,3 +49,5 @@ param set-default SIM_GZ_WH_DIS1 100
4949
# Steering
5050
param set-default SIM_GZ_SV_FUNC1 201
5151
param set-default SIM_GZ_SV_REV 1
52+
param set-default SIM_GZ_SV_MIN1 1500
53+
param set-default SIM_GZ_SV_MAX1 2100

ROMFS/px4fmu_common/init.d-posix/airframes/4030_gz_tiltrotor

+4-4
Original file line numberDiff line numberDiff line change
@@ -77,10 +77,10 @@ param set-default SIM_GZ_SV_FUNC3 203
7777
param set-default SIM_GZ_SV_FUNC4 204
7878
param set-default SIM_GZ_SV_FUNC5 205
7979

80-
param set-default SIM_GZ_SV_MAX4 27000
81-
param set-default SIM_GZ_SV_MIN4 18000
82-
param set-default SIM_GZ_SV_MAX5 27000
83-
param set-default SIM_GZ_SV_MIN5 18000
80+
param set-default SIM_GZ_SV_MAX4 2700
81+
param set-default SIM_GZ_SV_MIN4 1800
82+
param set-default SIM_GZ_SV_MAX5 2700
83+
param set-default SIM_GZ_SV_MIN5 1800
8484

8585
param set-default NPFG_PERIOD 12
8686
param set-default FW_PR_FF 0.2

Tools/module_config/generate_params.py

+4
Original file line numberDiff line numberDiff line change
@@ -284,9 +284,13 @@ def add_local_param(param_name, param_def):
284284
'''
285285
minimum_description = \
286286
'''Minimum output value (when not disarmed).
287+
Servo output represents angles [-180,180] with an offset of 180 deg, and a scaling of 10.
288+
Ex. ailerons of -45 deg would be 1350. (Must be coherent with joint limits in the airframe/model.sdf)
287289
'''
288290
maximum_description = \
289291
'''Maxmimum output value (when not disarmed).
292+
Servo output represents angles [-180,180] deg with an offset of 180 deg, and a scaling of 10.
293+
Ex. ailerons of 45 deg would be 2250. (Must be coherent with joint limits in the airframe/model.sdf)
290294
'''
291295
failsafe_description = \
292296
'''This is the output value that is set when in failsafe mode.

src/modules/simulation/gz_bridge/GZMixingInterfaceServo.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -64,8 +64,8 @@ bool GZMixingInterfaceServo::updateOutputs(bool stop_motors, uint16_t outputs[MA
6464
for (auto &servo_pub : _servos_pub) {
6565
if (_mixing_output.isFunctionSet(i)) {
6666
gz::msgs::Double servo_output;
67-
///TODO: Normalize output data
68-
double output = (outputs[i] - 500) / 500.0;
67+
double output = math::radians((double)outputs[i] / 10. - 180.);;
68+
6969
// std::cout << "outputs[" << i << "]: " << outputs[i] << std::endl;
7070
// std::cout << " output: " << output << std::endl;
7171
servo_output.set_data(output);

src/modules/simulation/gz_bridge/module.yaml

+4-4
Original file line numberDiff line numberDiff line change
@@ -20,10 +20,10 @@ actuator_output:
2020
group_label: 'Servos'
2121
channel_label: 'Servo'
2222
standard_params:
23-
disarmed: { min: 0, max: 1000, default: 500 }
24-
min: { min: 0, max: 1000, default: 0 }
25-
max: { min: 0, max: 1000, default: 1000 }
26-
failsafe: { min: 0, max: 1000 }
23+
disarmed: { min: 0, max: 3600, default: 1800 }
24+
min: { min: 0, max: 3600, default: 1350 }
25+
max: { min: 0, max: 3600, default: 2250 }
26+
failsafe: { min: 0, max: 3600 }
2727
num_channels: 8
2828
- param_prefix: SIM_GZ_WH
2929
group_label: 'Wheels'

0 commit comments

Comments
 (0)