Browse Source

mavlink: add HYGROMETER_SENSOR stream

master
honglang 3 years ago committed by Daniel Agar
parent
commit
17a99bc827
  1. 11
      src/modules/mavlink/mavlink_main.cpp
  2. 6
      src/modules/mavlink/mavlink_messages.cpp
  3. 84
      src/modules/mavlink/streams/HYGROMETER_SENSOR.hpp

11
src/modules/mavlink/mavlink_main.cpp

@ -1497,15 +1497,16 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream) @@ -1497,15 +1497,16 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
configure_stream_local("ESC_STATUS", 1.0f);
configure_stream_local("ESTIMATOR_STATUS", 0.5f);
configure_stream_local("EXTENDED_SYS_STATE", 1.0f);
configure_stream_local("GLOBAL_POSITION_INT", 5.0f);
configure_stream_local("GIMBAL_DEVICE_ATTITUDE_STATUS", 1.0f);
configure_stream_local("GIMBAL_MANAGER_STATUS", 0.5f);
configure_stream_local("GIMBAL_DEVICE_SET_ATTITUDE", 5.0f);
configure_stream_local("GIMBAL_MANAGER_STATUS", 0.5f);
configure_stream_local("GLOBAL_POSITION_INT", 5.0f);
configure_stream_local("GPS2_RAW", 1.0f);
configure_stream_local("GPS_GLOBAL_ORIGIN", 0.1f);
configure_stream_local("GPS_RAW_INT", 1.0f);
configure_stream_local("GPS_STATUS", 1.0f);
configure_stream_local("HOME_POSITION", 0.5f);
configure_stream_local("HYGROMETER_SENSOR", 0.1f);
configure_stream_local("LOCAL_POSITION_NED", 1.0f);
configure_stream_local("NAV_CONTROLLER_OUTPUT", 1.0f);
configure_stream_local("OBSTACLE_DISTANCE", 1.0f);
@ -1558,14 +1559,15 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream) @@ -1558,14 +1559,15 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
configure_stream_local("ESTIMATOR_STATUS", 1.0f);
configure_stream_local("EXTENDED_SYS_STATE", 5.0f);
configure_stream_local("GIMBAL_DEVICE_ATTITUDE_STATUS", 1.0f);
configure_stream_local("GIMBAL_MANAGER_STATUS", 0.5f);
configure_stream_local("GIMBAL_DEVICE_SET_ATTITUDE", 5.0f);
configure_stream_local("GIMBAL_MANAGER_STATUS", 0.5f);
configure_stream_local("GLOBAL_POSITION_INT", 50.0f);
configure_stream_local("GPS2_RAW", unlimited_rate);
configure_stream_local("GPS_GLOBAL_ORIGIN", 1.0f);
configure_stream_local("GPS_RAW_INT", unlimited_rate);
configure_stream_local("GPS_STATUS", 1.0f);
configure_stream_local("HOME_POSITION", 0.5f);
configure_stream_local("HYGROMETER_SENSOR", 1.0f);
configure_stream_local("NAV_CONTROLLER_OUTPUT", 10.0f);
configure_stream_local("OPTICAL_FLOW_RAD", 10.0f);
configure_stream_local("ORBIT_EXECUTION_STATUS", 5.0f);
@ -1627,6 +1629,7 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream) @@ -1627,6 +1629,7 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
configure_stream_local("GPS_GLOBAL_ORIGIN", 1.0f);
configure_stream_local("GPS_RAW_INT", 1.0f);
configure_stream_local("HOME_POSITION", 0.5f);
configure_stream_local("HYGROMETER_SENSOR", 1.0f);
configure_stream_local("NAV_CONTROLLER_OUTPUT", 1.5f);
configure_stream_local("OPTICAL_FLOW_RAD", 1.0f);
configure_stream_local("ORBIT_EXECUTION_STATUS", 5.0f);
@ -1662,6 +1665,7 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream) @@ -1662,6 +1665,7 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
configure_stream_local("GLOBAL_POSITION_INT", 10.0f);
configure_stream_local("GPS_RAW_INT", 1.0f);
configure_stream_local("HOME_POSITION", 0.5f);
configure_stream_local("HYGROMETER_SENSOR", 0.1f);
configure_stream_local("RC_CHANNELS", 5.0f);
configure_stream_local("SERVO_OUTPUT_RAW_0", 1.0f);
configure_stream_local("SYS_STATUS", 5.0f);
@ -1708,6 +1712,7 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream) @@ -1708,6 +1712,7 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
configure_stream_local("GPS_STATUS", 1.0f);
configure_stream_local("HIGHRES_IMU", 50.0f);
configure_stream_local("HOME_POSITION", 0.5f);
configure_stream_local("HYGROMETER_SENSOR", 1.0f);
configure_stream_local("MAG_CAL_REPORT", 1.0f);
configure_stream_local("MANUAL_CONTROL", 5.0f);
configure_stream_local("NAV_CONTROLLER_OUTPUT", 10.0f);

6
src/modules/mavlink/mavlink_messages.cpp

@ -79,13 +79,14 @@ @@ -79,13 +79,14 @@
#include "streams/GLOBAL_POSITION_INT.hpp"
#include "streams/GPS_GLOBAL_ORIGIN.hpp"
#include "streams/GPS_RAW_INT.hpp"
#include "streams/GPS_STATUS.hpp"
#include "streams/GPS_RTCM_DATA.hpp"
#include "streams/GPS_STATUS.hpp"
#include "streams/HEARTBEAT.hpp"
#include "streams/HIGHRES_IMU.hpp"
#include "streams/HIL_ACTUATOR_CONTROLS.hpp"
#include "streams/HIL_STATE_QUATERNION.hpp"
#include "streams/HOME_POSITION.hpp"
#include "streams/HYGROMETER_SENSOR.hpp"
#include "streams/LANDING_TARGET.hpp"
#include "streams/LOCAL_POSITION_NED.hpp"
#include "streams/MAG_CAL_REPORT.hpp"
@ -420,6 +421,9 @@ static const StreamListItem streams_list[] = { @@ -420,6 +421,9 @@ static const StreamListItem streams_list[] = {
#if defined(HOME_POSITION_HPP)
create_stream_list_item<MavlinkStreamHomePosition>(),
#endif // HOME_POSITION_HPP
#if defined(HYGROMETER_SENSOR_HPP)
create_stream_list_item<MavlinkStreamHygrometerSensor>(),
#endif // HYGROMETER_SENSOR_HPP
#if defined(SERVO_OUTPUT_RAW_HPP)
create_stream_list_item<MavlinkStreamServoOutputRaw<0> >(),
create_stream_list_item<MavlinkStreamServoOutputRaw<1> >(),

84
src/modules/mavlink/streams/HYGROMETER_SENSOR.hpp

@ -0,0 +1,84 @@ @@ -0,0 +1,84 @@
/****************************************************************************
*
* Copyright (c) 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.
*
****************************************************************************/
#ifndef HYGROMETER_SENSOR_HPP
#define HYGROMETER_SENSOR_HPP
#include <uORB/SubscriptionMultiArray.hpp>
#include <uORB/topics/sensor_hygrometer.h>
class MavlinkStreamHygrometerSensor : public MavlinkStream
{
public:
static MavlinkStream *new_instance(Mavlink *mavlink) { return new MavlinkStreamHygrometerSensor(mavlink); }
static constexpr const char *get_name_static() { return "HYGROMETER_SENSOR"; }
static constexpr uint16_t get_id_static() { return MAVLINK_MSG_ID_HYGROMETER_SENSOR; }
const char *get_name() const override { return get_name_static(); }
uint16_t get_id() override { return get_id_static(); }
unsigned get_size() override
{
return _sensor_hygrometer_subs.advertised_count() * (MAVLINK_MSG_ID_HYGROMETER_SENSOR_LEN +
MAVLINK_NUM_NON_PAYLOAD_BYTES);
}
private:
explicit MavlinkStreamHygrometerSensor(Mavlink *mavlink) : MavlinkStream(mavlink) {}
uORB::SubscriptionMultiArray<sensor_hygrometer_s> _sensor_hygrometer_subs{ORB_ID::sensor_hygrometer};
bool send() override
{
bool updated = false;
for (int i = 0; i < _sensor_hygrometer_subs.size(); i++) {
sensor_hygrometer_s sensor_hygrometer;
if (_sensor_hygrometer_subs[i].update(&sensor_hygrometer)) {
mavlink_hygrometer_sensor_t msg{};
msg.id = i; // uint8_t Hygrometer ID
msg.temperature = roundf(sensor_hygrometer.temperature * 100.f); // degrees to centidegrees (int16_t)
msg.humidity = roundf(sensor_hygrometer.humidity); // % (uint16_t)
mavlink_msg_hygrometer_sensor_send_struct(_mavlink->get_channel(), &msg);
updated = true;
}
}
return updated;
}
};
#endif // HYGROMETER_SENSOR_HPP
Loading…
Cancel
Save