px4-firmware/msg
Junwoo Hwang 2542b1bb26 Implement Pacakge delivery via Gripper during mission
This feature allows user to use a Gripper type pacakge delivery
mechanism on a drone to trigger the delivery during a mission via the
mission item `DO_GRIPPER`.

This is a minimal change that is intended to have simplest pacakge
delivery feature on PX4, however the future scope would extend this
feature out of Navigator, and rather move towards a federated PX4
(flight-mode flexibility) architecture. But until then, this will serve
the purpose.

Update Tools/sitl_gazebo submodule to remove sdf file overwrite error

- There was an error happening due to .sdf file being overwritten, it
was caused by a wrongfully added. sdf file.
- This update pulls in the PR commit: https://github.com/Auterion/sitl_gazebo/pull/147

Initial cut on supporing PAYLOAD_PLACE mission item

Tidy and comment on navigation.h to clarify mission item definition

- Convert vehicle command ack subscription data type to
SubscriptionData, to not care about having a dedicated struct for
copying the latest data
- Tidy and comment on navigation.h to clarify the definition of
mission_item_s, which is confusing as it is an intergration of MAVLink
Standard into PX4's internal Mission Item structure

Rename mission_block's mission item reached function & cleanup navigator

- Isolated Handle Vehicle Commands function inside the Navigator
- Rename mission_block's mission item reached function to 'reached or
completed', as the navigation command can also be an action (e.g.
DO_SET_SERVO, which doesn't make sense to refer to as 'reached' when we
have successfully done executed the command)

Include MAVLink PR commit to include payload_drop message

More changes to add payload_drop MAVLink message support

- Comitting for testing purposes

Add mission item payload_drop to vehicle command payload drop link

- Now with a mission item with the nav_cmd set to 'payload drop', the
appropriate 'payload drop' vehicle command will be issued

Make Payload drop executable via Mission Plan

Implement payload_drop module to simulate payload delivery

- Simple module that acknowledges the payload drop vehicle command after
certain time, to simulate a successful delivery

Additional changes - payload drop module not working yet

- Need to do more thread stuff to make it work :(

Fix Payload Drop enum mismatch in vehicle_command enums

- First functional Payload Drop Implementation MVP
- Simple Ack & resuming mission from Navigator tested successfully

Hold the position while executing payload drop mission item

- Still the position hold is not solid, maybe I am missing something in
the position setpoint part and all the internal implications of
Navigator :(

Add DO_WINCH command support

Some fixes after rebase on develop branch

- Some missed brackets
- Some comment edits, etc

Add DO_WINCH command support

- Still has a problem of flying away from the waypoint while the
DO_WINCH is being executed, probably position setpoint related stuff :(

Apply braking of the vehicle for DO_WINCH command

- Copies the behavior of NAV_CMD_DELAY, which executes a smooth, braking
behavior when executing the delay because of the braking condition in
`set_mission_items` function
- This will not apply to Fixed wings
- The payload deploy getting triggered may be too early, as right now as
soon as the vehicle approaches the waypoint within the acceptance
threshold, the payload gets deployed

Add DO_GRIPPER support

Implement Gripper actual Hardware triggering support

- Currently not working, possibly in the mixer there's a bug
- Implemented the publishing of actuator_controls_1 uORB topic
- Implemented the test command for the payload_drop module, to test the
grpiper functionality
- Edited px4board file to include the payload_drop module
- Added Holybro X500 V2 airframe file, to enable testing on X500 V2
- Created new Quad X Payload Delivery mixer, which maps the actuator
controls 1 topic's data into the MAIN pin 5 output

Make Payload Drop Gripper Work

- Initialization of the Gripper position to CLOSED on Constructor of the
payload_drop module
- Setting the OPEN and CLOSED value to the appropriate actuator controls
input

Set vehicle_command_ack message's timestamp correctly

- By not setting the timestamp, the ack commands were not correctly
graphed in PlotJuggler!

Rename payload drop module to payload deliverer

- I think it's a more complex name (harder to type), but more generic

Add Gripper class (WIP)

Add Gripper class functionalities

- Add gripper uORB message
- Add gripper state machine

Use Gripper class as main interface in payload_deliverer

- Utilizes Gripper class functions for doing Gripper functionality

Remove mixer based package delivery trigger logic

- Remove custom mixer files that mapped actuator controls to outputs
statically

Additional improvements of the payload_deliverer

Fix payload_deliverer module not starting

- _task_id wasn't geting set appropriately in task_spawn function, which
led to runtime failure

Add Gripper Function to mixer_module

- Still not showing up as function mapping in QGC, needs fix

Add parameters to control gripper behavior

- Now user can enable / disable gripper
- Also select which type of gripper to use

Applying review from nuno

Remove timeout fetching from mission item and use gripper's timeout

- Previously, it was planned to use a custom DO_GRIPPER and DO_WINCH
MAVLink message definitions with information on timeout, but since now
we are using original message definition, only relevant timeout
information is defined in the payload_deliverer class

- This change brings in the timeout parameter to the Navigator, which
then sets the timeout in the mission_block class level, which then
processes the timeout logic

Make payload deployment work for Allmend test :P

Support gripper open/close test commands in payload_deliverer

Move enum definition for GRIPPER_ACTION to vehicle_command.msg

Remove double call for ` ${R}etc/init.d/rc.vehicle_setup`

- Was introduced during the rebase
- Was causing module already running & uORB topic can't be advertised
errors

Fix format via `make format` command

Modify S500 airframe file to use for control allocation usage

- Added Control allocation related parameters as default to not have it
reset every time the airframe is selected

Implement mission specific payload deploy timeout and more changes

Switch payload_deliverer to run on work queue

Remove unnecessary files

- Airframe changes from enabling control allocation are removed

Address review comments

- Remove debug messages
- Remove unnecessary or verbose comments & code
- Properly call parameter_update() function

Switch payload_deliverer to scheduled interval work item & refactor

- Switch to Schedeuled on Interval Work Item, as previous vehicle
command subscription callback based behavior led to vehicle comamnd ack
not being sent accordingly (since the Run() wouldn't be called unless
there's a new vehicle command), leading to ack command not being sent
out
- Also, old vehicle commands were getting fetched due to the
subscription callback as well, which was removed with this patch
- Fix the wrong population of floating point param2 field of vehicle
command by int8_t type gripper action by creating dedicated function
- Refactor and add comments to increase readability

Add gripper::grabbing() method and handle this in parameter update

- Previously, the intermediate state 'grabbing' was not considered, and
when the parameter update was called after the first initialization of
the gripper, the grab() function was being called again, which would
produce unnecessary duplicate vehicle command.
- Also replaced direct .grab() access to sending vehicle comamnd, which
unifies the gripper actuation mechanism through vehicle commands.

Navigator: Change SubscriptionData to Subscription to reduce memory usage

- Also removed unused vehicle command ack sub

PayloadDeliverer: Remove unnecessary changes & Bring back vehicle_command sub cb
2022-09-07 08:11:52 +02:00
..
templates Robustify RTPS bridge stream parsing. 2022-07-20 01:13:47 -04:00
tools Docs are now in user guide and main (#19977) 2022-08-01 11:39:39 +10:00
CMakeLists.txt Implement Pacakge delivery via Gripper during mission 2022-09-07 08:11:52 +02:00
action_request.msg Use action_request to command RC VTOL transitions 2021-11-09 16:05:25 +01:00
actuator_armed.msg Mavlink FLIGHT_INFORMATION fix arming time (ms -> us) and add takeoff time 2020-12-16 09:38:05 -05:00
actuator_controls.msg use actuator_controls[8] for collective tilt for tiltrotor VTOL, instead of [4] 2022-05-03 15:11:21 +02:00
actuator_controls_status.msg mc_rate: compute control energy and publish to status msg 2021-10-02 18:12:05 -04:00
actuator_motors.msg esc_report: add actuator_function 2022-05-12 07:58:56 +02:00
actuator_outputs.msg hitl,sitl,sih: use separate actuator_outputs_sim for SYS_CTRL_ALLOC==1 2022-02-25 08:30:58 +01:00
actuator_servos.msg Whitespace cleanup. 2021-10-19 13:29:26 -04:00
actuator_servos_trim.msg control_allocator: implement trim + slew rate limits configuration 2021-12-24 20:06:13 -05:00
actuator_test.msg control_allocator: increase max num motors to 12 2022-05-10 08:57:39 +02:00
adc_report.msg ADC: replace ioctl with uorb message (#14087) 2020-03-20 11:23:32 +01:00
airspeed.msg Spelling errors (#19935) 2022-07-27 14:33:16 +10:00
airspeed_validated.msg Commenting and formating fixes 2020-10-06 09:31:58 +02:00
airspeed_wind.msg AirspeedSelector: add _CAS_scale_validated to airspeed_wind for logging 2021-10-22 17:00:35 +02:00
autotune_attitude_control_status.msg mc atune: add multicopter attitude auto-tuner module 2021-10-02 18:12:05 -04:00
battery_status.msg Spelling errors (#19935) 2022-07-27 14:33:16 +10:00
button_event.msg safety and safety button: refactoring #19413 2022-04-05 07:57:37 +02:00
camera_capture.msg add timestamp field to uORB msgs; sync timestamp whenever possible 2018-08-09 13:40:48 +02:00
camera_status.msg mavlink: use dynamic camera comp id instead of hardcoded value 2021-07-31 12:41:49 -04:00
camera_trigger.msg Fix camera trigger via MAVLink when camera capture feedback is enabled 2021-12-17 07:56:08 +01:00
cellular_status.msg Spelling errors (#19935) 2022-07-27 14:33:16 +10:00
collision_constraints.msg first push on supporting ROS2 Dashing and IDL 4.2 2019-10-04 16:56:03 +01:00
collision_report.msg add timestamp field to uORB msgs; sync timestamp whenever possible 2018-08-09 13:40:48 +02:00
commander_state.msg Added VTOL Takeoff navigation mode (#19027) 2022-02-15 14:56:57 +01:00
control_allocator_status.msg control_allocator: remove failed motor from effectiveness 2022-05-12 07:58:56 +02:00
cpuload.msg add timestamp field to uORB msgs; sync timestamp whenever possible 2018-08-09 13:40:48 +02:00
debug_array.msg Add support for mavlink message DEBUG_FLOAT_ARRAY 2018-09-27 12:33:12 -04:00
debug_key_value.msg add timestamp field to uORB msgs; sync timestamp whenever possible 2018-08-09 13:40:48 +02:00
debug_value.msg add timestamp field to uORB msgs; sync timestamp whenever possible 2018-08-09 13:40:48 +02:00
debug_vect.msg add timestamp field to uORB msgs; sync timestamp whenever possible 2018-08-09 13:40:48 +02:00
differential_pressure.msg Spelling errors (#19935) 2022-07-27 14:33:16 +10:00
distance_sensor.msg Drivers: Distance Sensors: Add proper device IDs 2021-01-27 17:02:20 -05:00
ekf2_timestamps.msg ekf2_timestamps.msg - make first line a complete sentence 2021-08-16 08:29:44 +02:00
esc_report.msg esc_report: add actuator_function 2022-05-12 07:58:56 +02:00
esc_status.msg msg: extend field definition in msg/esc_report (arming & failure states) 2020-04-03 09:16:43 +02:00
estimator_aid_source_1d.msg ekf2: use estimator_aid_src for all yaw sources (mag, gnss, ev) 2022-07-29 11:20:48 -04:00
estimator_aid_source_2d.msg ekf2: estimator aid source status (starting with fake position) 2022-05-23 16:21:49 -04:00
estimator_aid_source_3d.msg ekf2: add AUX velocity aid src status 2022-07-29 12:02:31 -04:00
estimator_bias.msg ekf2: publish GNSS, rng and EV height biases 2022-08-24 09:16:11 -04:00
estimator_event_flags.msg Spelling errors (#19935) 2022-07-27 14:33:16 +10:00
estimator_gps_status.msg ekf2: add new estimator_gps_status.msg 2022-02-21 08:58:59 -05:00
estimator_innovations.msg Spelling errors (#19935) 2022-07-27 14:33:16 +10:00
estimator_selector_status.msg Multi-EKF support (ekf2) 2020-10-27 10:56:11 -04:00
estimator_sensor_bias.msg save significant IMU bias changes learned by the EKF 2021-11-07 15:34:27 -05:00
estimator_states.msg estimator messages add explicit timestamp_sample 2020-09-04 10:48:26 -04:00
estimator_status.msg ekf: add range finder "faulty" status 2022-02-11 10:57:45 -05:00
estimator_status_flags.msg ekf2: use estimator_aid_src for all yaw sources (mag, gnss, ev) 2022-07-29 11:20:48 -04:00
event.msg commander: rework arming checks to use the events interface 2022-08-25 22:02:15 -04:00
failure_detector_status.msg failure_detector: add motor/ESC failure detection 2022-05-12 07:58:56 +02:00
follow_target.msg New follow-me flight task 2022-06-16 16:14:57 -04:00
follow_target_estimator.msg New follow-me flight task 2022-06-16 16:14:57 -04:00
follow_target_status.msg FollowMe : Replace First order target position filter with Second order position and velocity filter 2022-06-16 16:14:57 -04:00
generator_status.msg mavlink: handle receiving GENERATOR_STATUS 2020-09-25 11:36:58 -04:00
geofence_result.msg Format whitespace and group checkall() methods together in geofence class. 2022-01-31 21:01:03 -05:00
gimbal_device_attitude_status.msg mavlink: don't send gimbal_device_attitude_status 2022-02-07 19:21:15 -05:00
gimbal_device_information.msg vmount/mavlink: update gimbal information message 2021-02-17 13:54:34 -05:00
gimbal_device_set_attitude.msg Support for gimbal v2 protocol 2021-02-17 13:54:34 -05:00
gimbal_manager_information.msg vmount/mavlink: update gimbal information message 2021-02-17 13:54:34 -05:00
gimbal_manager_set_attitude.msg vmount/navigator/mavlink: gimbal v2 changes 2021-02-17 13:54:34 -05:00
gimbal_manager_set_manual_control.msg vmount/navigator/mavlink: gimbal v2 changes 2021-02-17 13:54:34 -05:00
gimbal_manager_status.msg vmount/navigator/mavlink: gimbal v2 changes 2021-02-17 13:54:34 -05:00
gps_dump.msg Spelling errors (#19935) 2022-07-27 14:33:16 +10:00
gps_inject_data.msg Support two RTCM links with the same corrections 2022-07-15 08:20:27 +02:00
gripper.msg Implement Pacakge delivery via Gripper during mission 2022-09-07 08:11:52 +02:00
health_report.msg arming checks: add health topic 2022-08-25 22:02:15 -04:00
heater_status.msg Create publish_status() method in the heater driver, add a status field to indicate if the temperature setpoint has been met within 2.5C, breakout update_params() method from the Heater::Run() method and simplify logic. 2021-04-16 08:09:51 -04:00
home_position.msg Commander: set home position in air 2020-12-07 10:24:23 -05:00
hover_thrust_estimate.msg mc_hover_thrust_estimator: validity flag and other small improvements/fixes 2020-08-03 10:30:52 -04:00
input_rc.msg Spelling errors (#19935) 2022-07-27 14:33:16 +10:00
internal_combustion_engine_status.msg Add internal combustion engine status uavcan bridge and mavlink EFI_STATUS stream 2021-07-30 22:31:43 -04:00
iridiumsbd_status.msg Spelling errors (#19935) 2022-07-27 14:33:16 +10:00
irlock_report.msg add timestamp field to uORB msgs; sync timestamp whenever possible 2018-08-09 13:40:48 +02:00
landing_gear.msg vehicle constraints: remove landing gear 2018-12-10 16:17:23 +01:00
landing_target_innovations.msg add timestamp field to uORB msgs; sync timestamp whenever possible 2018-08-09 13:40:48 +02:00
landing_target_pose.msg add timestamp field to uORB msgs; sync timestamp whenever possible 2018-08-09 13:40:48 +02:00
led_control.msg Spelling errors (#19935) 2022-07-27 14:33:16 +10:00
log_message.msg log_message increase queue depth 2->4 2021-01-09 11:04:32 -05:00
logger_status.msg logger: record message gaps 2020-07-29 13:36:22 -04:00
mag_worker_data.msg Add logging of mag calibration data (mag_worker_data) 2021-01-20 09:44:45 -05:00
magnetometer_bias_estimate.msg magnetometer allow setting initial calibration from bias if available and stable 2021-12-01 20:24:56 -05:00
manual_control_setpoint.msg Use backwards compatible manual_control_setpoint instead of manual_control_input 2021-11-09 16:05:25 +01:00
manual_control_switches.msg helicopter: add switch to engage main motor 2022-09-07 08:00:26 +02:00
mavlink_log.msg mavlink: STATUSTEXT directly use mavlink_log subscription 2020-11-17 19:47:06 -05:00
mavlink_tunnel.msg Enable logging of mavlink tunnel messages 2022-01-26 11:10:43 -05:00
mission.msg beautify some identation 2018-08-09 13:40:48 +02:00
mission_result.msg beautify some identation 2018-08-09 13:40:48 +02:00
mount_orientation.msg beautify some identation 2018-08-09 13:40:48 +02:00
navigator_mission_item.msg navigator: publish navigator mission item changes for logging 2020-10-13 12:12:03 -04:00
npfg_status.msg integrate optional NPFG library for wind-aware fixed-wing guidance 2022-01-14 22:05:53 +01:00
obstacle_distance.msg Collision Prevention: support multiple sensors and frames (#12883) 2019-09-06 08:38:56 +02:00
offboard_control_mode.msg Enable offboard actuator setpoints 2021-11-07 15:38:42 -05:00
onboard_computer_status.msg Add units on message comments 2019-10-27 11:47:10 +00:00
orb_test.msg uORB: add bitset for faster orb_exists check and remove uORB::Subscription lazy subscribe hack/optimization 2020-03-11 09:06:33 -04:00
orb_test_large.msg uORB: add bitset for faster orb_exists check and remove uORB::Subscription lazy subscribe hack/optimization 2020-03-11 09:06:33 -04:00
orb_test_medium.msg fix: uORB topics lost messages when publications overflow 2020-10-19 08:52:55 +02:00
orbit_status.msg Orbit: Add RC controlled yaw mode 2020-07-13 20:26:13 +02:00
parameter_update.msg parameter_update.msg: add basic status info 2021-02-12 08:27:47 -05:00
ping.msg add timestamp field to uORB msgs; sync timestamp whenever possible 2018-08-09 13:40:48 +02:00
position_controller_landing_status.msg msg/position_controller_landing_status.msg: fix constant name conventions 2022-07-28 11:29:03 -04:00
position_controller_status.msg position_controller_status message: added comments regarding NAN 2021-03-31 11:23:33 +02:00
position_setpoint.msg added comment for cruising throttle only affecting rover 2022-07-12 09:07:20 +02:00
position_setpoint_triplet.msg add timestamp field to uORB msgs; sync timestamp whenever possible 2018-08-09 13:40:48 +02:00
power_button_state.msg add timestamp field to uORB msgs; sync timestamp whenever possible 2018-08-09 13:40:48 +02:00
power_monitor.msg Added TI ina226 I2C power monitor (#11755) 2019-05-17 13:33:48 -04:00
pps_capture.msg Remove PPS GPIO interrupt when the rate is higher than 20Hz 2022-07-04 11:32:33 +02:00
pwm_input.msg PWM automatic trigger system (ATS) for parachutes (#13726) 2020-01-06 20:14:06 -05:00
px4io_status.msg px4io: replace safety_off state with safety button event (#19558) 2022-06-01 13:15:13 -04:00
radio_status.msg radio_status: change 'fixed' field name to 'fix' so it does not clash with 'fixed' floating-point notation on the IDL generation 2018-10-08 10:58:45 +02:00
rate_ctrl_status.msg FW attitue controller: fix publishing of rate controller status 2022-08-19 09:40:48 +02:00
rc_channels.msg helicopter: add switch to engage main motor 2022-09-07 08:00:26 +02:00
rc_parameter_map.msg add timestamp field to uORB msgs; sync timestamp whenever possible 2018-08-09 13:40:48 +02:00
rpm.msg Spelling errors (#19935) 2022-07-27 14:33:16 +10:00
rtl_time_estimate.msg Compute RTL time and react if lower than flight time 2021-11-24 14:10:24 +01:00
satellite_info.msg Add MavlinkStreamGPSStatus status class stream via GPS_STATUS.hpp and add PRN code to satellite_info.msg. 2020-10-14 08:26:42 +02:00
sensor_accel.msg sensors/vehicle_imu: vehicle_imu_status include accel/gyro full raw FIFO sample rate 2021-02-24 08:13:53 -05:00
sensor_accel_fifo.msg rotate accel/gyro FIFO before publish and fix angular velocity filter resets 2021-03-22 12:01:12 -04:00
sensor_baro.msg sensors: add baro calibration and cleanup 2022-03-26 16:08:41 -04:00
sensor_combined.msg Add gyro clipping to mirror accel clipping monitoring instances. 2022-05-18 21:16:05 -04:00
sensor_correction.msg sensor calibration: save temperature at calibration time for monitoring 2021-08-15 11:19:24 -04:00
sensor_gnss_relative.msg drives/gps: add new sensor_gnsss_relative msg 2022-03-29 07:59:41 +02:00
sensor_gps.msg Support two RTCM links with the same corrections 2022-07-15 08:20:27 +02:00
sensor_gyro.msg Add gyro clipping to mirror accel clipping monitoring instances. 2022-05-18 21:16:05 -04:00
sensor_gyro_fft.msg gyro_fft: change default length 1024 -> 512 to decrease latency 2021-07-06 21:54:18 -04:00
sensor_gyro_fifo.msg rotate accel/gyro FIFO before publish and fix angular velocity filter resets 2021-03-22 12:01:12 -04:00
sensor_hygrometer.msg Spelling errors (#19935) 2022-07-27 14:33:16 +10:00
sensor_mag.msg sensors (accel/gyro/mag) determine if external with device id 2022-01-10 10:31:07 -05:00
sensor_optical_flow.msg optical flow sensor pipeline overhaul 2022-06-20 20:56:56 -04:00
sensor_preflight_mag.msg sensors: move mag aggregation to new VehicleMagnetometer WorkItem 2020-08-21 10:12:13 -04:00
sensor_selection.msg sensors: move mag aggregation to new VehicleMagnetometer WorkItem 2020-08-21 10:12:13 -04:00
sensors_status.msg sensors: add baro calibration and cleanup 2022-03-26 16:08:41 -04:00
sensors_status_imu.msg sensors: add accel/gyro current priority to sensors_status_imu 2021-07-30 21:20:01 -04:00
system_power.msg adc: add support for multiple sensor voltage channels 2021-01-15 10:57:20 -05:00
takeoff_status.msg Spelling errors (#19935) 2022-07-27 14:33:16 +10:00
task_stack_info.msg load_mon: update orb_publish to uORB::Publication<> 2019-09-02 20:41:34 -04:00
tecs_status.msg log tecs trim throttle 2022-07-12 09:07:20 +02:00
telemetry_status.msg mavlink increase HEARTBEAT timeout 1.5->2.5s 2022-02-18 10:16:20 -05:00
test_motor.msg commander: add support for DO_MOTOR_TEST 2019-10-24 09:27:29 +02:00
timesync.msg timesync: remove system ID field from the timesync message 2021-08-12 08:44:53 +02:00
timesync_status.msg microRTPS: agent: publish timesync status 2021-08-12 08:44:53 +02:00
trajectory_bezier.msg Add documenation to uORB message 2020-03-09 09:51:49 +01:00
trajectory_setpoint.msg trajectory_setpoint: correct comment typo "kinematically" 2022-05-12 17:19:48 +02:00
trajectory_waypoint.msg add point type (mavlink command associated with wp) in Obstacle Avoidance interface 2019-08-05 16:05:40 +02:00
transponder_report.msg fix: uORB topics lost messages when publications overflow 2020-10-19 08:52:55 +02:00
tune_control.msg Reduce Beeepr Default volume : 40 -> 20, since it's too loud for TAP_ESC devices from Yuneec (#19311) 2022-03-11 10:27:57 +01:00
uavcan_parameter_request.msg fix: uORB topics lost messages when publications overflow 2020-10-19 08:52:55 +02:00
uavcan_parameter_value.msg add timestamp field to uORB msgs; sync timestamp whenever possible 2018-08-09 13:40:48 +02:00
ulog_stream.msg fix: uORB topics lost messages when publications overflow 2020-10-19 08:52:55 +02:00
ulog_stream_ack.msg ulog stream msgs: rename 'sequence' fields as they are protected names in fastrtpsgen 2019-10-14 16:37:17 +01:00
uwb_distance.msg Spelling errors (#19935) 2022-07-27 14:33:16 +10:00
uwb_grid.msg Support for NXP UWB position sensor 2022-04-04 17:26:52 +02:00
vehicle_acceleration.msg Clarification of coordinate systems for sensors_* and vehicle_* messages (#16339) 2020-12-15 09:18:05 +01:00
vehicle_air_data.msg sensors: add baro calibration and cleanup 2022-03-26 16:08:41 -04:00
vehicle_angular_acceleration.msg Clarification of coordinate systems for sensors_* and vehicle_* messages (#16339) 2020-12-15 09:18:05 +01:00
vehicle_angular_acceleration_setpoint.msg initial control allocation support 2021-01-18 11:25:37 -05:00
vehicle_angular_velocity.msg Clarification of coordinate systems for sensors_* and vehicle_* messages (#16339) 2020-12-15 09:18:05 +01:00
vehicle_attitude.msg Add gyro clipping to mirror accel clipping monitoring instances. 2022-05-18 21:16:05 -04:00
vehicle_attitude_setpoint.msg fixed-wing: update rate controller integrator handling 2022-08-19 09:40:48 +02:00
vehicle_command.msg Implement Pacakge delivery via Gripper during mission 2022-09-07 08:11:52 +02:00
vehicle_command_ack.msg Move Vehicle Command Result Enum defs to Vehicle Command Ack (#19729) 2022-07-07 16:15:11 +02:00
vehicle_constraints.msg vehicle_constraints: remove deprecated speed_xy constraint 2021-11-09 21:47:06 -05:00
vehicle_control_mode.msg px4io: moving mixing to FMU side 2021-09-25 19:15:05 -04:00
vehicle_global_position.msg Multi-EKF support (ekf2) 2020-10-27 10:56:11 -04:00
vehicle_imu.msg Add gyro clipping to mirror accel clipping monitoring instances. 2022-05-18 21:16:05 -04:00
vehicle_imu_status.msg Add gyro clipping to mirror accel clipping monitoring instances. 2022-05-18 21:16:05 -04:00
vehicle_land_detected.msg move vehicle at rest detection ekf2 -> land_detector 2022-02-01 17:50:19 -05:00
vehicle_local_position.msg vehicle_local_position: fixed comment 2022-08-02 15:29:25 +02:00
vehicle_local_position_setpoint.msg vehicle_local_position_setpoint: reorder fields for clarity 2022-05-12 17:19:48 +02:00
vehicle_magnetometer.msg Clarification of coordinate systems for sensors_* and vehicle_* messages (#16339) 2020-12-15 09:18:05 +01:00
vehicle_odometry.msg msg/vehicle_odometry.msg: simplify covariance handling and update all usage (#19966) 2022-08-04 12:55:21 -04:00
vehicle_optical_flow.msg optical flow sensor pipeline overhaul 2022-06-20 20:56:56 -04:00
vehicle_optical_flow_vel.msg optical flow sensor pipeline overhaul 2022-06-20 20:56:56 -04:00
vehicle_rates_setpoint.msg vehicle_rates_setpoint: log wheel controller yaw rate on common yaw rate channel 2022-07-18 10:49:27 -04:00
vehicle_roi.msg beautify some identation 2018-08-09 13:40:48 +02:00
vehicle_status.msg commander: move battery handling into arming checks 2022-09-01 17:07:23 -04:00
vehicle_status_flags.msg commander: move esc checks to arming check 2022-09-01 17:07:23 -04:00
vehicle_thrust_setpoint.msg vehicle_{thrust,torque}_setpoint.msg: fix comment 2022-04-28 19:51:28 -04:00
vehicle_torque_setpoint.msg vehicle_{thrust,torque}_setpoint.msg: fix comment 2022-04-28 19:51:28 -04:00
vehicle_trajectory_bezier.msg Add uORB messages for bezier curve trajectories 2020-03-09 09:51:49 +01:00
vehicle_trajectory_waypoint.msg TRAJECTORY message renamed 2018-11-13 12:13:01 -05:00
vtol_vehicle_status.msg VTOL: remove some unsued variables 2022-05-18 10:01:04 +02:00
wheel_encoders.msg Changed wheel encoder publication to multi-instance 2019-08-05 02:45:33 -07:00
wind.msg select single system-wide wind estimate message (current best) 2021-02-20 13:15:01 -05:00
yaw_estimator_status.msg ekf2: yaw estimator add yaw_composite_valid boolean 2022-06-01 13:16:06 -04:00