/**************************************************************************** * * Copyright (c) 2012-2021 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * 1. Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * 2. Redistributions in binary form must reproduce the above copyright * notice, this list of conditions and the following disclaimer in * the documentation and/or other materials provided with the * distribution. * 3. Neither the name PX4 nor the names of its contributors may be * used to endorse or promote products derived from this software * without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. * ****************************************************************************/ /** * @file mavlink_receiver.h * MAVLink receiver thread * * @author Lorenz Meier * @author Anton Babushkin */ #pragma once #include "mavlink_ftp.h" #include "mavlink_log_handler.h" #include "mavlink_mission.h" #include "mavlink_parameters.h" #include "mavlink_timesync.h" #include "tune_publisher.h" #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #if !defined(CONSTRAINED_FLASH) # include # include # include # include #endif // !CONSTRAINED_FLASH using namespace time_literals; class Mavlink; class MavlinkReceiver : public ModuleParams { public: MavlinkReceiver(Mavlink *parent); ~MavlinkReceiver() override; void start(); void stop(); void print_detailed_rx_stats() const; private: static void *start_trampoline(void *context); void run(); void acknowledge(uint8_t sysid, uint8_t compid, uint16_t command, uint8_t result); /** * Common method to handle both mavlink command types. T is one of mavlink_command_int_t or mavlink_command_long_t. */ template void handle_message_command_both(mavlink_message_t *msg, const T &cmd_mavlink, const vehicle_command_s &vehicle_command); uint8_t handle_request_message_command(uint16_t message_id, float param2 = 0.0f, float param3 = 0.0f, float param4 = 0.0f, float param5 = 0.0f, float param6 = 0.0f, float param7 = 0.0f); void handle_message(mavlink_message_t *msg); void handle_message_adsb_vehicle(mavlink_message_t *msg); void handle_message_att_pos_mocap(mavlink_message_t *msg); void handle_message_battery_status(mavlink_message_t *msg); void handle_message_cellular_status(mavlink_message_t *msg); void handle_message_collision(mavlink_message_t *msg); void handle_message_command_ack(mavlink_message_t *msg); void handle_message_command_int(mavlink_message_t *msg); void handle_message_command_long(mavlink_message_t *msg); void handle_message_distance_sensor(mavlink_message_t *msg); void handle_message_follow_target(mavlink_message_t *msg); void handle_message_generator_status(mavlink_message_t *msg); void handle_message_set_gps_global_origin(mavlink_message_t *msg); void handle_message_gps_rtcm_data(mavlink_message_t *msg); void handle_message_heartbeat(mavlink_message_t *msg); void handle_message_hil_gps(mavlink_message_t *msg); void handle_message_hil_optical_flow(mavlink_message_t *msg); void handle_message_hil_sensor(mavlink_message_t *msg); void handle_message_hil_state_quaternion(mavlink_message_t *msg); void handle_message_landing_target(mavlink_message_t *msg); void handle_message_logging_ack(mavlink_message_t *msg); void handle_message_manual_control(mavlink_message_t *msg); void handle_message_obstacle_distance(mavlink_message_t *msg); void handle_message_odometry(mavlink_message_t *msg); void handle_message_onboard_computer_status(mavlink_message_t *msg); void handle_message_optical_flow_rad(mavlink_message_t *msg); void handle_message_ping(mavlink_message_t *msg); void handle_message_play_tune(mavlink_message_t *msg); void handle_message_play_tune_v2(mavlink_message_t *msg); void handle_message_radio_status(mavlink_message_t *msg); void handle_message_rc_channels_override(mavlink_message_t *msg); void handle_message_serial_control(mavlink_message_t *msg); void handle_message_set_actuator_control_target(mavlink_message_t *msg); void handle_message_set_attitude_target(mavlink_message_t *msg); void handle_message_set_mode(mavlink_message_t *msg); void handle_message_set_position_target_global_int(mavlink_message_t *msg); void handle_message_set_position_target_local_ned(mavlink_message_t *msg); void handle_message_statustext(mavlink_message_t *msg); void handle_message_trajectory_representation_bezier(mavlink_message_t *msg); void handle_message_trajectory_representation_waypoints(mavlink_message_t *msg); void handle_message_utm_global_position(mavlink_message_t *msg); void handle_message_vision_position_estimate(mavlink_message_t *msg); void handle_message_gimbal_manager_set_attitude(mavlink_message_t *msg); void handle_message_gimbal_manager_set_manual_control(mavlink_message_t *msg); void handle_message_gimbal_device_information(mavlink_message_t *msg); #if !defined(CONSTRAINED_FLASH) void handle_message_debug(mavlink_message_t *msg); void handle_message_debug_float_array(mavlink_message_t *msg); void handle_message_debug_vect(mavlink_message_t *msg); void handle_message_named_value_float(mavlink_message_t *msg); #endif // !CONSTRAINED_FLASH void CheckHeartbeats(const hrt_abstime &t, bool force = false); /** * Set the interval at which the given message stream is published. * The rate is the number of messages per second. * * @param msgId The ID of the message interval to be set. * @param interval The interval in usec to send the message. * @param data_rate The total link data rate in bytes per second. * * @return PX4_OK on success, PX4_ERROR on fail. */ int set_message_interval(int msgId, float interval, int data_rate = -1); void get_message_interval(int msgId); /** * Decode a switch position from a bitfield and state. */ int decode_switch_pos_n(uint16_t buttons, unsigned sw); bool evaluate_target_ok(int command, int target_system, int target_component); void fill_thrust(float *thrust_body_array, uint8_t vehicle_type, float thrust); void schedule_tune(const char *tune); void update_rx_stats(const mavlink_message_t &message); px4::atomic_bool _should_exit{false}; pthread_t _thread {}; Mavlink *_mavlink; MavlinkFTP _mavlink_ftp; MavlinkLogHandler _mavlink_log_handler; MavlinkMissionManager _mission_manager; MavlinkParametersManager _parameters_manager; MavlinkTimesync _mavlink_timesync; mavlink_status_t _status{}; ///< receiver status, used for mavlink_parse_char() orb_advert_t _mavlink_log_pub{nullptr}; static constexpr int MAX_REMOTE_COMPONENTS{8}; struct ComponentState { uint32_t last_time_received_ms{0}; uint32_t received_messages{0}; uint32_t missed_messages{0}; uint8_t system_id{0}; uint8_t component_id{0}; uint8_t last_sequence{0}; }; ComponentState _component_states[MAX_REMOTE_COMPONENTS] {}; bool _warned_component_states_full_once{false}; uint64_t _total_received_counter{0}; ///< The total number of successfully received messages uint64_t _total_lost_counter{0}; ///< Total messages lost during transmission. uint8_t _mavlink_status_last_buffer_overrun{0}; uint8_t _mavlink_status_last_parse_error{0}; uint16_t _mavlink_status_last_packet_rx_drop_count{0}; // ORB publications uORB::Publication _actuator_controls_pubs[4] {ORB_ID(actuator_controls_0), ORB_ID(actuator_controls_1), ORB_ID(actuator_controls_2), ORB_ID(actuator_controls_3)}; uORB::Publication _airspeed_pub{ORB_ID(airspeed)}; uORB::Publication _battery_pub{ORB_ID(battery_status)}; uORB::Publication _cellular_status_pub{ORB_ID(cellular_status)}; uORB::Publication _collision_report_pub{ORB_ID(collision_report)}; uORB::Publication _differential_pressure_pub{ORB_ID(differential_pressure)}; uORB::Publication _follow_target_pub{ORB_ID(follow_target)}; uORB::Publication _gimbal_manager_set_attitude_pub{ORB_ID(gimbal_manager_set_attitude)}; uORB::Publication _gimbal_manager_set_manual_control_pub{ORB_ID(gimbal_manager_set_manual_control)}; uORB::Publication _gimbal_device_information_pub{ORB_ID(gimbal_device_information)}; uORB::Publication _irlock_report_pub{ORB_ID(irlock_report)}; uORB::Publication _landing_target_pose_pub{ORB_ID(landing_target_pose)}; uORB::Publication _log_message_pub{ORB_ID(log_message)}; uORB::Publication _obstacle_distance_pub{ORB_ID(obstacle_distance)}; uORB::Publication _offboard_control_mode_pub{ORB_ID(offboard_control_mode)}; uORB::Publication _onboard_computer_status_pub{ORB_ID(onboard_computer_status)}; uORB::Publication _generator_status_pub{ORB_ID(generator_status)}; uORB::Publication _flow_pub{ORB_ID(optical_flow)}; uORB::Publication _sensor_gps_pub{ORB_ID(sensor_gps)}; uORB::Publication _attitude_pub{ORB_ID(vehicle_attitude)}; uORB::Publication _att_sp_pub{ORB_ID(vehicle_attitude_setpoint)}; uORB::Publication _mc_virtual_att_sp_pub{ORB_ID(mc_virtual_attitude_setpoint)}; uORB::Publication _fw_virtual_att_sp_pub{ORB_ID(fw_virtual_attitude_setpoint)}; uORB::Publication _global_pos_pub{ORB_ID(vehicle_global_position)}; uORB::Publication _land_detector_pub{ORB_ID(vehicle_land_detected)}; uORB::Publication _local_pos_pub{ORB_ID(vehicle_local_position)}; uORB::Publication _trajectory_setpoint_pub{ORB_ID(trajectory_setpoint)}; uORB::Publication _mocap_odometry_pub{ORB_ID(vehicle_mocap_odometry)}; uORB::Publication _visual_odometry_pub{ORB_ID(vehicle_visual_odometry)}; uORB::Publication _rates_sp_pub{ORB_ID(vehicle_rates_setpoint)}; uORB::Publication _trajectory_bezier_pub{ORB_ID(vehicle_trajectory_bezier)}; uORB::Publication _trajectory_waypoint_pub{ORB_ID(vehicle_trajectory_waypoint)}; #if !defined(CONSTRAINED_FLASH) uORB::Publication _debug_array_pub {ORB_ID(debug_array)}; uORB::Publication _debug_key_value_pub{ORB_ID(debug_key_value)}; uORB::Publication _debug_value_pub{ORB_ID(debug_value)}; uORB::Publication _debug_vect_pub{ORB_ID(debug_vect)}; #endif // !CONSTRAINED_FLASH // ORB publications (multi) uORB::PublicationMulti _distance_sensor_pub{ORB_ID(distance_sensor)}; uORB::PublicationMulti _flow_distance_sensor_pub{ORB_ID(distance_sensor)}; uORB::PublicationMulti _rc_pub{ORB_ID(input_rc)}; uORB::PublicationMulti _manual_control_setpoint_pub{ORB_ID(manual_control_setpoint)}; uORB::PublicationMulti _ping_pub{ORB_ID(ping)}; uORB::PublicationMulti _radio_status_pub{ORB_ID(radio_status)}; // ORB publications (queue length > 1) uORB::Publication _gps_inject_data_pub{ORB_ID(gps_inject_data)}; uORB::Publication _transponder_report_pub{ORB_ID(transponder_report)}; uORB::Publication _cmd_pub{ORB_ID(vehicle_command)}; uORB::Publication _cmd_ack_pub{ORB_ID(vehicle_command_ack)}; // ORB subscriptions uORB::Subscription _actuator_armed_sub{ORB_ID(actuator_armed)}; uORB::Subscription _home_position_sub{ORB_ID(home_position)}; uORB::Subscription _vehicle_attitude_sub{ORB_ID(vehicle_attitude)}; uORB::Subscription _vehicle_local_position_sub{ORB_ID(vehicle_local_position)}; uORB::Subscription _vehicle_global_position_sub{ORB_ID(vehicle_global_position)}; uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)}; uORB::Subscription _actuator_controls_3_sub{ORB_ID(actuator_controls_3)}; uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; // hil_sensor and hil_state_quaternion enum SensorSource { ACCEL = 0b111, GYRO = 0b111000, MAG = 0b111000000, BARO = 0b1101000000000, DIFF_PRESS = 0b10000000000 }; PX4Accelerometer *_px4_accel{nullptr}; PX4Barometer *_px4_baro{nullptr}; PX4Gyroscope *_px4_gyro{nullptr}; PX4Magnetometer *_px4_mag{nullptr}; static constexpr unsigned int MOM_SWITCH_COUNT{8}; uint8_t _mom_switch_pos[MOM_SWITCH_COUNT] {}; uint16_t _mom_switch_state{0}; hrt_abstime _last_utm_global_pos_com{0}; // Allocated if needed. TunePublisher *_tune_publisher{nullptr}; hrt_abstime _last_heartbeat_check{0}; hrt_abstime _heartbeat_type_antenna_tracker{0}; hrt_abstime _heartbeat_type_gcs{0}; hrt_abstime _heartbeat_type_onboard_controller{0}; hrt_abstime _heartbeat_type_gimbal{0}; hrt_abstime _heartbeat_type_adsb{0}; hrt_abstime _heartbeat_type_camera{0}; hrt_abstime _heartbeat_component_telemetry_radio{0}; hrt_abstime _heartbeat_component_log{0}; hrt_abstime _heartbeat_component_osd{0}; hrt_abstime _heartbeat_component_obstacle_avoidance{0}; hrt_abstime _heartbeat_component_visual_inertial_odometry{0}; hrt_abstime _heartbeat_component_pairing_manager{0}; hrt_abstime _heartbeat_component_udp_bridge{0}; hrt_abstime _heartbeat_component_uart_bridge{0}; DEFINE_PARAMETERS( (ParamFloat) _param_bat_crit_thr, (ParamFloat) _param_bat_emergen_thr, (ParamFloat) _param_bat_low_thr, (ParamFloat) _param_sens_flow_maxhgt, (ParamFloat) _param_sens_flow_maxr, (ParamFloat) _param_sens_flow_minhgt, (ParamInt) _param_sens_flow_rot ); // Disallow copy construction and move assignment. MavlinkReceiver(const MavlinkReceiver &) = delete; MavlinkReceiver operator=(const MavlinkReceiver &) = delete; };