Browse Source

control_allocator: increase max num motors to 12

main
Beat Küng 3 years ago
parent
commit
32402f31df
  1. 8
      msg/actuator_motors.msg
  2. 2
      msg/actuator_test.msg
  3. 2
      src/lib/mixer_module/output_functions.yaml
  4. 2
      src/modules/control_allocator/ActuatorEffectiveness/ActuatorEffectivenessRotors.hpp
  5. 10
      src/modules/control_allocator/module.yaml

8
msg/actuator_motors.msg

@ -4,7 +4,7 @@ uint64 timestamp_sample # the timestamp the data this control response is ba
uint16 reversible_flags # bitset which motors are configured to be reversible uint16 reversible_flags # bitset which motors are configured to be reversible
uint8 NUM_CONTROLS = 8 uint8 NUM_CONTROLS = 12
float32[8] control # range: [-1, 1], where 1 means maximum positive thrust, float32[12] control # range: [-1, 1], where 1 means maximum positive thrust,
# -1 maximum negative (if not supported by the output, <0 maps to NaN), # -1 maximum negative (if not supported by the output, <0 maps to NaN),
# and NaN maps to disarmed (stop the motors) # and NaN maps to disarmed (stop the motors)

2
msg/actuator_test.msg

@ -7,7 +7,7 @@ uint8 ACTION_RELEASE_CONTROL = 0 # exit test mode for the given function
uint8 ACTION_DO_CONTROL = 1 # enable actuator test mode uint8 ACTION_DO_CONTROL = 1 # enable actuator test mode
uint8 FUNCTION_MOTOR1 = 101 uint8 FUNCTION_MOTOR1 = 101
uint8 MAX_NUM_MOTORS = 8 uint8 MAX_NUM_MOTORS = 12
uint8 FUNCTION_SERVO1 = 201 uint8 FUNCTION_SERVO1 = 201
uint8 MAX_NUM_SERVOS = 8 uint8 MAX_NUM_SERVOS = 8

2
src/lib/mixer_module/output_functions.yaml

@ -9,7 +9,7 @@ functions:
Motor: Motor:
start: 101 start: 101
count: 8 count: 12
Servo: Servo:
start: 201 start: 201
count: 8 count: 8

2
src/modules/control_allocator/ActuatorEffectiveness/ActuatorEffectivenessRotors.hpp

@ -60,7 +60,7 @@ public:
FixedUpwards, ///< axis is fixed, pointing upwards (negative Z) FixedUpwards, ///< axis is fixed, pointing upwards (negative Z)
}; };
static constexpr int NUM_ROTORS_MAX = 8; static constexpr int NUM_ROTORS_MAX = 12;
struct RotorGeometry { struct RotorGeometry {
matrix::Vector3f position; matrix::Vector3f position;

10
src/modules/control_allocator/module.yaml

@ -1,4 +1,4 @@
__max_num_mc_motors: &max_num_mc_motors 8 __max_num_mc_motors: &max_num_mc_motors 12
__max_num_servos: &max_num_servos 8 __max_num_servos: &max_num_servos 8
__max_num_tilts: &max_num_tilts 4 __max_num_tilts: &max_num_tilts 4
@ -58,6 +58,10 @@ parameters:
5: Motor 6 5: Motor 6
6: Motor 7 6: Motor 7
7: Motor 8 7: Motor 8
8: Motor 9
9: Motor 10
10: Motor 11
11: Motor 12
default: 0 default: 0
CA_R${i}_SLEW: CA_R${i}_SLEW:
description: description:
@ -111,6 +115,10 @@ parameters:
6: '6' 6: '6'
7: '7' 7: '7'
8: '8' 8: '8'
9: '9'
10: '10'
11: '11'
12: '12'
default: 0 default: 0
CA_ROTOR${i}_PX: CA_ROTOR${i}_PX:
description: description:

Loading…
Cancel
Save