Claudio Micheli
8a01135a93
Commander: more changes to use events with escs and battery failures
...
Signed-off-by: Claudio Micheli <claudio@auterion.com>
2022-01-13 08:40:34 +01:00
Claudio Micheli
d122513197
extend support for Battery status message
...
Signed-off-by: Claudio Micheli <claudio@auterion.com>
2022-01-13 08:40:34 +01:00
Julian Oes
9fe7a40673
manual_control: enable sending camera commands
2022-01-10 23:04:10 -05:00
Julian Oes
860b23dd17
tunes: add tune to power off
...
This is used by the ATL Mantis EDU to help the user realize when the
drone is powered off.
2022-01-10 23:04:10 -05:00
Daniel Agar
e731fcdbc0
sensors (accel/gyro/mag) determine if external with device id
2022-01-10 10:31:07 -05:00
Matthias Grob
bbb04ab4b8
Remove relaying of maximum altitude through land detector
2022-01-05 14:54:59 +01:00
honglang
b60e59d9be
msg: new sensor_hygrometer msg
2021-12-27 12:13:09 -05:00
Beat Küng
4c80adfaf1
control_allocator: implement trim + slew rate limits configuration
2021-12-24 20:06:13 -05:00
Beat Küng
1901edf13c
actuator_motors.msg: add reversible flags & implement in mixer_module
2021-12-24 20:06:13 -05:00
Matthias Grob
f68ae39840
Commander: avoid RC actions during calibration
2021-12-22 09:08:23 -05:00
marcojob
2cfe08b3b1
small typo in vehicle_local_position msg
2021-12-17 15:45:07 +01:00
Michael Schaeuble
5ad8b84dec
Fix PPS based UTC timestamp in camera trigger and capture messages
...
The existing implementation has about 100ms difference to a reference clock. With the changes this error less than 25us.
- Use sensor_gps messages with hrt timestamps as RTC reference and not the system realtime clock. The PPS interrupt can then be aligned with the GPS clock system.
- Keep fallback based on system RTC when no PPS pulse was captured
2021-12-17 07:56:08 +01:00
Michael Schaeuble
ebb657bcf4
Fix camera trigger via MAVLink when camera capture feedback is enabled
...
- camera_trigger module always publishes the camera_trigger msg (independent of the camera feedback)
- Use camera_trigger msg and set the feedback flag
- Subscribing modules determine if the message is relevant based on the feedback message
2021-12-17 07:56:08 +01:00
Igor Mišić
72b1db4a63
pps_capture: implementation of pulse per second capture driver
2021-12-17 07:56:08 +01:00
Thomas Debrunner
eb69f15d3a
health-flags: Increase health flags to 64 bit bit field to support extended sys status mavlink message
...
Add SYS_STATUS flag for parachute
2021-12-14 09:41:12 -05:00
Beat Küng
f76086ffa1
microRTPS_agent_CMakeLists.txt.em: add install section
2021-12-10 09:03:08 -05:00
Matthias Grob
ddc6b6bc9c
battery: move MAVLink specific handling out of battery class
2021-12-07 21:06:51 +01:00
Daniel Agar
8fbf79527f
magnetometer allow setting initial calibration from bias if available and stable
2021-12-01 20:24:56 -05:00
alexklimaj
bfd5a90a5d
UAVCAN Moving Baseline Working
...
Set uavcan publisher priorities
Switch to ardupilot rtcm message and add heading accuracy
2021-11-30 15:59:08 -05:00
Matthias Grob
c522a8b15a
Compute RTL time and react if lower than flight time
...
- Compute RTL time also during RTL
- Calculate correct altitude when finding destination
2021-11-24 14:10:24 +01:00
Beat Küng
a0e43bca96
msg: remove unused vehicle_actuator_setpoint topic
2021-11-23 12:40:22 -05:00
Beat Küng
21699935e8
vehicle_command: add VEHICLE_CMD_ACTUATOR_TEST and VEHICLE_CMD_CONFIGURE_ACTUATOR
2021-11-23 12:40:22 -05:00
Beat Küng
6fdcc43ea8
mixer_module: add testing for SYS_CTRL_ALLOC=1 with actuator_test cmd+uorb msg
2021-11-23 12:40:22 -05:00
Matthias Grob
3193b554ca
Add optional preflight check for healthy MAVLink parachute system
2021-11-19 17:15:04 +01:00
Matthias Grob
43c529f294
Add MAVLink parachute system heartbeat detection
2021-11-19 17:15:04 +01:00
bresch
f751dd2242
FlightTask: set yaw_setpoint to NAN when yaw should not be controlled
2021-11-16 18:09:37 -05:00
Matthias Grob
91c48606ee
battery_status: clearly define and handle zero remaining flight time
2021-11-15 15:44:02 +01:00
Matthias Grob
54f2e91775
battery_status: report remaining flight time in seconds
...
This allows more accurate reporting and is compliant with the
MAVLink interface.
2021-11-15 15:44:02 +01:00
Matthias Grob
7ec8dd9d23
vehicle_constraints: remove deprecated speed_xy constraint
2021-11-09 21:47:06 -05:00
bresch
d47f9f155a
MC mixer: replace multirotor_motor_limits by control_allocator_status
...
CA: fix saturation computation
Since the CA matrix is normalized, the same scale applied to be used when using the effectiveness matrix
MCRateControl: use control_allocator_status to get saturation info
2021-11-09 10:35:10 -05:00
Matthias Grob
fabf865411
Use backwards compatible manual_control_setpoint instead of manual_control_input
2021-11-09 16:05:25 +01:00
Matthias Grob
a593a51f05
Commander: fix mode initialization with RC
2021-11-09 16:05:25 +01:00
Matthias Grob
af54ac7cdb
ManualControl: remove unused variables and renaming
2021-11-09 16:05:25 +01:00
Matthias Grob
a349dae760
Use action_request to command RC VTOL transitions
2021-11-09 16:05:25 +01:00
Matthias Grob
956997eb1e
Replace arm_request and mode_request with combined action_request
...
Which saves flash space, log size and is extensible to handle e.g.
the VTOL transition and future actions.
2021-11-09 16:05:25 +01:00
Matthias Grob
052e29267d
Use mode_request for RC mode switching
2021-11-09 16:05:25 +01:00
Matthias Grob
f8e4846851
Use arm_request for manual killing
2021-11-09 16:05:25 +01:00
Matthias Grob
af607e3040
Use separate arm_request instead of vehicle_command for RC arming
2021-11-09 16:05:25 +01:00
Matthias Grob
7a2ef4a917
Commander: don't publish RC_IN_MODE to vehicle_status
...
This just contains the content of the parameter which
is redundant and results in multiple sources of truth.
2021-11-09 16:05:25 +01:00
Matthias Grob
93bed7f670
vehicle_command: shorten arming action/origin enum names
2021-11-09 16:05:25 +01:00
Julian Oes
b3a5072de5
commander/manual_control: use msg enum for params
...
Instead of using a private enum class we should define the enum in the
vehicle_command message and then use it consistently.
2021-11-09 16:05:25 +01:00
Julian Oes
6a6b8d49fc
msg: re-use manual_control_input in setpoint
...
This way we avoid duplication between manual_control_input and
manual_control_setpoint.
2021-11-09 16:05:25 +01:00
Julian Oes
baf81abbab
msg: whitespace only
2021-11-09 16:05:25 +01:00
Julian Oes
bd0c1014d9
manual_control: support arming button
...
The arming button required some refactoring in order to support to
toggle arm/disarm using the vehicle_command. Otherwise manual_control
would have to subscribe to the arming topic and we would spread out the
logic again, and risk race conditions.
2021-11-09 16:05:25 +01:00
Julian Oes
e49b596edc
commander: add desired main state
...
This is an intermediate solution to carry forward the initial state of
the mode slot. Basically, it allows that we start up in Stabilized but
switch to POSCTL as soon we have the required GPS.
2021-11-09 16:05:25 +01:00
Julian Oes
cda6524421
manual_control: move override detection
...
This also removes the option to ignore throttle for the override
detection as it's not really required anymore.
2021-11-09 16:05:25 +01:00
Julian Oes
723db8bf2a
manual_control: add selector class [WIP]
...
This adds a selector class with unit tests.
The idea is to have a valid flag in manual_control_septoint and set that
according to the selection and/or timeout of manual_control_inputs.
2021-11-09 16:05:25 +01:00
Daniel Agar
2d816e0b3e
[WIP] manual_control selector hacks
2021-11-09 16:05:25 +01:00
Daniel Agar
e18cf3da3e
sensors/vehicle_imu: use WelfordMean for online mean and variance
2021-11-09 15:19:35 +01:00
JaeyoungLim
cda7c6ceaa
Enable offboard actuator setpoints
2021-11-07 15:38:42 -05:00
Daniel Agar
68026eadeb
save significant IMU bias changes learned by the EKF
...
* ekf2: make publishing of learned accel biases more robust
* ekf2: reset accel bias if calibration updated
* msg: add separate accel and gyro calibration counters
* ekf2: use separate accel and gyro calibration counters
* ekf2: rework logic to reset biases when calibration counters increment
* sensors: add saving of learned accel biases
* ekf2: generalized saving accel/gyro/mag in flight sensor calibration
* boards: holybro kakutef7 disable systemcmds/perf and systemcmds/top to save flash
Co-authored-by: Paul Riseborough <gncsolns@gmail.com>
2021-11-07 15:34:27 -05:00
bresch
1e94512719
FD: use flags union instead of bitmask
2021-11-05 09:45:52 -04:00
bresch
3f1025fb1e
FD: add dedicated topic to log more internal states
...
log imbalanced propeller check metric
add failure_detector_status message
2021-11-05 09:45:52 -04:00
bresch
5dfb8e594a
FD: add imbalanced propeller check
2021-11-05 09:45:52 -04:00
bresch
bf2fb70d67
vehicleIMU: compute and log accel variance
2021-11-05 09:45:52 -04:00
Silvan Fuhrer
f02786d112
Navigator/Commander: make GPS failsafe consitent: switch to Descend also for FW and VTOL
...
- remove GPS failsafe mode
- for VTOL: transition to hover in Descend (unless NAV_FORCE_VT is not set)
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2021-11-05 12:09:39 +03:00
Silvan Fuhrer
cad7851774
AirspeedSelector: add _CAS_scale_validated to airspeed_wind for logging
...
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2021-10-22 17:00:35 +02:00
Silvan Fuhrer
625f556b0e
AirspeedSelector: airspeed scale estimation improvements and robustification
...
- run airspeed scale estimation always, not in dedicated mode
- add option to apply scale automatically, with extra feasibility check
- add airspeed scale for all 3 possible airspeed instances
- clean up parameters
- add check for data stuck (non-changing airspeed data)
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2021-10-22 17:00:35 +02:00
Beat Küng
8a2b310b83
topic_listener: avoid code generation, use existing metadata at runtime
...
This reduces flash size for v5 by ~110KB, the topic listener now only adds
about 1.2KB.
2021-10-20 08:10:05 +02:00
Beat Küng
4c73ac3805
uorb: use single byte for internal types in o_fields metadata
...
Reduces flash usage by ~9KB.
2021-10-20 08:10:05 +02:00
mcsauder
21163d859e
Whitespace cleanup.
2021-10-19 13:29:26 -04:00
Beat Küng
a65533b469
mixer_module: add output functions for servos, landing gear, parachute, RC passthrough & gimbal
2021-10-18 18:45:19 -04:00
Beat Küng
5103f00de3
vehicle_command.msg: add VEHICLE_CMD_DO_SET_ACTUATOR
2021-10-18 18:45:19 -04:00
Beat Küng
38fa65a47e
control_allocator: remove direct mixer, add actuator_{motors,servos} instead
2021-10-18 18:45:19 -04:00
bresch
ec178c8745
create new mag_bias_estimator module
...
Co-authored-by: Daniel Agar <daniel@agar.ca>
2021-10-02 21:25:21 -04:00
bresch
5874b1f87c
mc atune: add module to all targets
...
- adjust flash constrianed targets to fit
2021-10-02 18:12:05 -04:00
bresch
0498ee92d0
mc atune: add multicopter attitude auto-tuner module
2021-10-02 18:12:05 -04:00
bresch
d504b49695
mc_rate: compute control energy and publish to status msg
2021-10-02 18:12:05 -04:00
Nicolas Martin
b24e5fc0af
clean remaining offboard_control_signal_found_once
...
offboard_control_signal_found_once is not used any more
2021-09-28 09:25:04 -04:00
Daniel Agar
089c962d92
px4io: moving mixing to FMU side
...
Using mixers on the IO side had a remote benefit of being able to
override all control surfaces with a radio remote on a fixed wing.
This ended up not being used that much and since the original design
10 years ago (2011) we have been able to convince ourselves that the
overall system stability is at a level where this marginal benefit,
which is not present on multicopters, is not worth the hazzle.
Co-authored-by: Beat Küng <beat-kueng@gmx.net>
Co-authored-by: Daniel Agar <daniel@agar.ca>
2021-09-25 19:15:05 -04:00
Igor Mišić
3a148bc777
camera_trigger: remove camera trigger secondary
...
camera_trigger: publish trigger when capture feedback is not enabled
2021-09-23 09:21:56 +02:00
Hamish Willee
f41e5985e8
vehicle_local_position: clarify origin of system
2021-09-22 10:14:23 +02:00
Matthias Grob
d1f1e02afb
Refactor mode button changes
2021-09-14 09:52:32 +02:00
Claudio Micheli
c50daae4a3
rc_update: introduce support for toggle buttons via RC channels
...
Signed-off-by: Claudio Micheli <claudio@auterion.com>
2021-09-14 09:52:32 +02:00
Claudio Micheli
fa4fc5f347
esc_report: change esc_temperature field to allow negative values
...
Signed-off-by: Claudio Micheli <claudio@auterion.com>
2021-09-11 15:14:49 -04:00
Beat Küng
00d939995b
fix micrortps_transport: set poll fd when baudrate is 0
2021-08-22 10:42:13 -04:00
Christian Llanes
c0efbe1f9c
change PublicationMulti-> Publication as a temporary fix
2021-08-20 19:56:56 +01:00
Christian Llanes
6423ea50e6
add sensor_combined to urtps_bridge_topics.yaml
2021-08-18 23:52:45 +01:00
Hamish Willee
8aecc64a73
generate uorb - support multiline descriptions
2021-08-16 08:29:44 +02:00
Hamish Willee
9c081ed24b
ekf2_timestamps.msg - make first line a complete sentence
...
Fixes the docs.
2021-08-16 08:29:44 +02:00
Hamish Willee
51fa834ac6
generate_msg_docs: generate better page title
2021-08-16 08:29:44 +02:00
Daniel Agar
ff39e27e2d
sensor calibration: save temperature at calibration time for monitoring
2021-08-15 11:19:24 -04:00
Daniel Agar
f2bae02f87
msg: purge unused qshell
2021-08-14 12:54:01 -04:00
TSC21
21953daa3b
microRTPS: transport: fix UART configuration
2021-08-12 08:44:53 +02:00
TSC21
4b6646c5f3
microRTPS: transport: normalize configs with mavlink/mavlink-router
2021-08-12 08:44:53 +02:00
TSC21
af8a6117fa
microRTPS: agent: add missing 'g' option
2021-08-12 08:44:53 +02:00
TSC21
2a368b4db1
uorb_to_ros_urtps_topics: minor cleanup
2021-08-12 08:44:53 +02:00
TSC21
74557c9071
uorb_to_ros_msgs: minor cleanup
2021-08-12 08:44:53 +02:00
TSC21
8762dce762
microRTPS: transport: small format fix
2021-08-12 08:44:53 +02:00
TSC21
fae1627d92
microRTPS: client: cleanup and make arguments consistent
2021-08-12 08:44:53 +02:00
TSC21
109b031156
microRTPS: agent: cleanup and make arguments consistent
2021-08-12 08:44:53 +02:00
TSC21
e83a3a6cf7
microRTPS: update RTPS message list naming from 'ids' to 'msgs'
2021-08-12 08:44:53 +02:00
TSC21
0b23679f98
msg: templates: update empy contexts, required fields and license header years
2021-08-12 08:44:53 +02:00
TSC21
ffa70ac0fd
microRTPS: generate_microRTPS_bridge: run fastrtsgen only once for all files
...
Reducing the generation time to a 4th of the time (!!)
2021-08-12 08:44:53 +02:00
TSC21
a8a56a03a4
microRTPS: rename uorb_to_ros_rtps_ids to uorb_to_ros_urtps_topics and remove the 'id' references on it
2021-08-12 08:44:53 +02:00
TSC21
4609949bbb
microRTPS: generate_microRTPS_bridge: only run the generator for the topics that are actually marked to be used
2021-08-12 08:44:53 +02:00
TSC21
695e1fa574
uorb_to_ros_rtps_ids: add an header with a notice regarding the autogneration of the 'px4_ros_com' urtps_bridge_topics.yaml file
...
Although it can be modified manually, we are going to recommend the developer to generate it from the PX4-Autopilot side instead
2021-08-12 08:44:53 +02:00
TSC21
c478e2985a
microRTPS: simplify the attribution of the RTPS IDs by makiing it automatic
...
1. The RTPS IDs are now automatically assigned to the topics
2. Only the topics that get defined to be sent or received in the urtps_bridge_topics.yaml (renamed, since now it doesn't contain IDs) receive the IDs
3. Any addition or removal on the urtps_bridge_topics.yaml file might update the topic IDs - this will require that the agent and the client ID list has to be in sync. This will further require a robustification of the way we check the IDs and the message definitions when starting the bridge.
2021-08-12 08:44:53 +02:00
TSC21
ba3dbbd38d
microRTPS: send the system ID with the RTPS packet header and remove the need for extra id fields in uORB
...
This allows that all messages (not only timesync messages) that get received on the same system that sent them do not get parsed. As the microRTPS agent is built currently, this will only happen right now if someone sets the same UDP port to send and receive data, or by manually changing the agent topics (which were always autogenerated).
2021-08-12 08:44:53 +02:00
TSC21
a10dab516c
timesync: remove system ID field from the timesync message
2021-08-12 08:44:53 +02:00
TSC21
25dbffe1aa
microRTPS: agent: split FMU input from output topics in Pubs/Subs
2021-08-12 08:44:53 +02:00
TSC21
d31b7feb31
microRTPS: agent: publish timesync status
2021-08-12 08:44:53 +02:00
TSC21
a324e5465a
timesync: extend timesync_status message with protocol source field and enum
2021-08-12 08:44:53 +02:00
TSC21
6d4f65a47a
microRTPS: allow timesync using ROS time
2021-08-12 08:44:53 +02:00
Julian Oes
0c9fefce32
urtps: rectify comment
2021-08-12 08:44:53 +02:00
Julian Oes
31b1241de8
uorb_microcdr: collect all messages
...
Without this we are potentially too slow to collect them all which can
lead to the buffer in protocol_splitter to overflow and be reset.
2021-08-12 08:44:53 +02:00
bresch
01d0b8800e
commander: report GNSS yaw fault to user
2021-08-05 11:10:02 +02:00
Beat Küng
86dc35022a
generate_msg_docs.py: simplify logic a bit
2021-08-03 07:54:41 +02:00
Hamish Willee
bf59fd84ba
Add simple comment parser
2021-08-03 07:54:41 +02:00
Beat Küng
da6275e43a
msg: add script structure to generate docs from .msg files
2021-08-03 07:54:41 +02:00
Daniel Agar
93aa6e3f78
ekf2: baro bias publish minor cleanup
...
- naming consistency (estimator prefix as "namespace")
- only publish if baro is available and bias is changing as a small logging optimization
- avoid unnecessary copying (get const reference to status directly)
- trivial code style fixes
2021-08-02 13:59:38 -04:00
Igor Mišić
af2247bd94
mavlink: use dynamic camera comp id instead of hardcoded value
2021-07-31 12:41:49 -04:00
Dima Ponomarev
d08d0443bc
Add internal combustion engine status uavcan bridge and mavlink EFI_STATUS stream
2021-07-30 22:31:43 -04:00
Daniel Agar
713a1d08a3
sensors: add accel/gyro current priority to sensors_status_imu
...
- later the sensor priorities (user configurable) can be factored into the estimator selection criteria
2021-07-30 21:20:01 -04:00
TSC21
205d4400eb
add baro_bias_estimate to RTPS list
2021-07-20 04:56:33 -07:00
Oleg
8fbbf56c4d
microRTPS: fix setting UART communication flags
...
bitwise not should be used instead of logical not
2021-07-20 12:34:58 +02:00
bresch
54c7e74de3
EKF: add baro bias estimator using GNSS altitude
2021-07-19 16:53:45 -04:00
TSC21
e39e3b3418
events interface: chance uORB 'sequence' to 'event_sequence'
...
The reason is that sequence is an IDL reserved keyword, which results on failure when parsing with FastRTPSGen.
2021-07-09 13:24:13 +02:00
Beat Küng
e3972d563a
cmake: ensure generated source files exist before extracting events
...
Only needed for Makefile-based builds:
gmake[3]: *** No rule to make target 'src/modules/flight_mode_manager/FlightTasks_generated.hpp', needed by 'events/px4.json'. Stop.
2021-07-07 21:38:09 -04:00
Beat Küng
38f3b8d356
mavlink & system: add events interface
...
- sending protocol
- uorb event message & template methods for argument packing
- libevents submodule to send common events and handle json files
- cmake maintains a list of all (PX4) source files for the current build
(PX4 modules + libs), which is used to extract event metadata and
generate a json file
2021-07-07 21:38:09 -04:00
Daniel Agar
1b5e65df04
gyro_fft: change default length 1024 -> 512 to decrease latency
...
- change default FFT length (1024 -> 512)
- this doubles the update rate because half the number of samples are required for each
- decrease number of peaks (4 -> 3)
- so far 3 seems to be sufficient on most vehicles
- increase median filter window (3 -> 5)
- decrease SNR requirement (likely needs to be configurable)
2021-07-06 21:54:18 -04:00
Daniel Agar
a5ee28883a
gyro_fft: track FFT peaks and median filter frequency
2021-07-06 12:32:25 -04:00
Matthias Grob
b824f33ae9
battery: publish measured values also when battery not connected
2021-07-01 14:24:38 +02:00
Matthias Grob
9c0c85c9e2
battery_status: naming consistency current_filtered_a -> current_average_a
2021-07-01 14:24:38 +02:00
TSC21
4741ec25ce
microRTPS: increase base message ID space to 179
2021-06-25 13:05:24 +02:00
TSC21
0c5f2d3b8c
microRTPS: add missing header for PRIu32 and PRIu16 macros
...
Co-authored-by: squizz617 <seulbae@gatech.edu>
2021-06-21 16:36:44 +02:00
TSC21
084a992572
microRTPS: agent: only allow to whitelist the localhost when using FastDDS as the rmw
2021-06-21 16:36:44 +02:00
TSC21
79f7986715
apply ROS2 default memory management and publish mode QoS policies; make sure that SharedMemory is only used with FastDDS as the rmw
2021-06-21 16:36:44 +02:00
TSC21
d3a23cee40
microRTPS: agent: fix double free memory problem on SIGINT
...
It fixes also some minor issues when exiting the agent, including the printed stats
2021-06-21 16:36:44 +02:00
TSC21
6d5f12d2a2
microRTPS: client: add TX rate limiter
2021-06-21 16:36:44 +02:00
TSC21
ac2b38603c
microRTPS: client: add missing "-p" option for the UART poll timeout and use microsecs for the send/rcv thread sleeps
2021-06-21 16:36:44 +02:00
TSC21
0cc79f3e48
microRTPS: client: show diagnostic of current bandwidth usage on the 'status' option
2021-06-21 16:36:44 +02:00
TSC21
d6ee15596d
microRTPS: client: show diagnostic of average bandwidth usage on the 'status' option
2021-06-21 16:36:44 +02:00
TSC21
40462bfc1f
microRTPS: client: reduce name set by pthread_setname_np since Linux requires names (with NUL) to fit in 16 chars, otherwise returns ERANGE (34)
2021-06-21 16:36:44 +02:00
TSC21
773d81f208
microRTPS: client: fix send per allocated topic
2021-06-21 16:36:44 +02:00
TSC21
f2fad6d966
microRTPS: by default, when FastDDS >= 2.0, enable Shared Memory transport for the agent participants when the localhost network is enabled
2021-06-21 16:36:44 +02:00
TSC21
320b414511
microRTPS: client: match the code style from the PX4 Firmware
2021-06-21 16:36:44 +02:00
TSC21
63571b3e3f
microRTPS: agent: match the code style from the PX4 Firmware
2021-06-21 16:36:44 +02:00
TSC21
323ce797f8
microRTPS: allow communications only in the localhost network when ROS_LOCALHOST_ONLY env variable is set
2021-06-21 16:36:44 +02:00
TSC21
578e426e9e
microRTPS: set trajectory_waypoint to be sent only, as this is outgoing data with vehicle_trajectory_waypoint_desired
2021-06-21 16:36:44 +02:00
David Sidrane
026d36dee8
microRTPS:Use inttypes
2021-06-16 17:07:47 +02:00
David Sidrane
64db89ab20
px_generate_uorb_topic_helper: Use inttypes
2021-06-16 17:07:47 +02:00
Julian Oes
e828ba4288
commander: send parachute command on termination ( #17564 )
...
* commander: send parachute command on termination
This sends the DO_PARACHUTE command to parachute component.
* commander: fix lying comments and printf
* commander: use one flag for termination triggered
This merges the duplicate flags _flight_termination_triggered and
_flight_flight_termination_printed.
* commander: correct variable name
* commander: always send tune with parachute
* commander: fix target_component for parachute cmd
The previous changes were wrong in that all commands were now sent to
the parachute component which doesn't make any sense. Of course only the
parachute command should be sent there.
2021-06-15 11:50:30 +02:00
bresch
514845592b
en-/disable mc position controller using explicit control mode flag
2021-06-09 18:10:22 +02:00
RomanBapst
b06b46b224
log raw airspeed derivative, pitch setpoint and airspeed innovation for TECS
...
Signed-off-by: RomanBapst <bapstroman@gmail.com>
2021-05-31 23:56:23 +02:00
Daniel Agar
2a792ca201
gyro_fft: add simple SNR requirement and reduce number of peaks
2021-05-31 10:26:45 -04:00
Nuno Marques
f9fe0e3746
ROS2/microRTPS: Add support for ROS2 Galactic and ROS2 Rolling ( #17664 )
...
microRTPS: generate_microRTPS_bridge: add support for ROS2 versions
* Galactic
* Rolling
2021-05-27 09:32:16 -07:00
Damien SIX
e4f235001b
fix timesync for timestamp sample (including SFINAE detection)
2021-05-16 13:15:37 -04:00
RomanBapst
3b27864e53
vehicle_status: added field for geofence violation
...
Signed-off-by: RomanBapst <bapstroman@gmail.com>
2021-05-10 10:46:49 +03:00
RomanBapst
269ce07cb5
land detector: log more states in order to facilitate debugging ground contact state
...
Signed-off-by: RomanBapst <bapstroman@gmail.com>
2021-05-04 16:43:33 +02:00