mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-22 10:27:36 +08:00
mavlink: streams fix SCALED_IMU size reporting
This commit is contained in:
@@ -98,6 +98,8 @@
|
||||
#include "streams/RAW_RPM.hpp"
|
||||
#include "streams/RC_CHANNELS.hpp"
|
||||
#include "streams/SCALED_IMU.hpp"
|
||||
#include "streams/SCALED_IMU2.hpp"
|
||||
#include "streams/SCALED_IMU3.hpp"
|
||||
#include "streams/SCALED_PRESSURE.hpp"
|
||||
#include "streams/SERVO_OUTPUT_RAW.hpp"
|
||||
#include "streams/STATUSTEXT.hpp"
|
||||
@@ -333,10 +335,14 @@ static const StreamListItem streams_list[] = {
|
||||
create_stream_list_item<MavlinkStreamHighresIMU>(),
|
||||
#endif // HIGHRES_IMU_HPP
|
||||
#if defined(SCALED_IMU_HPP)
|
||||
create_stream_list_item<MavlinkStreamScaledIMU<0> >(),
|
||||
create_stream_list_item<MavlinkStreamScaledIMU<1> >(),
|
||||
create_stream_list_item<MavlinkStreamScaledIMU<2> >(),
|
||||
create_stream_list_item<MavlinkStreamScaledIMU>(),
|
||||
#endif // SCALED_IMU_HPP
|
||||
#if defined(SCALED_IMU2_HPP)
|
||||
create_stream_list_item<MavlinkStreamScaledIMU2>(),
|
||||
#endif // SCALED_IMU2_HPP
|
||||
#if defined(SCALED_IMU3_HPP)
|
||||
create_stream_list_item<MavlinkStreamScaledIMU3>(),
|
||||
#endif // SCALED_IMU3_HPP
|
||||
#if defined(SCALED_PRESSURE)
|
||||
create_stream_list_item<MavlinkStreamScaledPressure>(),
|
||||
#endif // SCALED_PRESSURE
|
||||
|
||||
@@ -1,6 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2020 PX4 Development Team. All rights reserved.
|
||||
* 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
|
||||
@@ -37,163 +37,78 @@
|
||||
#include <lib/ecl/geo/geo.h>
|
||||
#include <lib/matrix/matrix/math.hpp>
|
||||
|
||||
#include <uORB/topics/vehicle_imu.h>
|
||||
#include <uORB/topics/sensor_mag.h>
|
||||
#include <uORB/topics/vehicle_imu.h>
|
||||
|
||||
using matrix::Vector3f;
|
||||
|
||||
static constexpr const char *MSG_NAMES_SCALED_IMU[] = {
|
||||
"SCALED_IMU",
|
||||
"SCALED_IMU2",
|
||||
"SCALED_IMU3"
|
||||
};
|
||||
|
||||
class MavlinkStreamScaledIMUBase : public MavlinkStream
|
||||
class MavlinkStreamScaledIMU : public MavlinkStream
|
||||
{
|
||||
protected:
|
||||
explicit MavlinkStreamScaledIMUBase(Mavlink *mavlink, int N) : MavlinkStream(mavlink),
|
||||
_raw_imu_sub(ORB_ID(vehicle_imu), N),
|
||||
_raw_mag_sub(ORB_ID(sensor_mag), N)
|
||||
{}
|
||||
public:
|
||||
static MavlinkStream *new_instance(Mavlink *mavlink) { return new MavlinkStreamScaledIMU(mavlink); }
|
||||
|
||||
static constexpr const char *get_name_static() { return "SCALED_IMU"; }
|
||||
static constexpr uint16_t get_id_static() { return MAVLINK_MSG_ID_SCALED_IMU; }
|
||||
|
||||
const char *get_name() const override { return get_name_static(); }
|
||||
uint16_t get_id() override { return get_id_static(); }
|
||||
|
||||
unsigned get_size() override
|
||||
{
|
||||
if (_vehicle_imu_sub.advertised() || _sensor_mag_sub.advertised()) {
|
||||
return MAVLINK_MSG_ID_SCALED_IMU_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
private:
|
||||
explicit MavlinkStreamScaledIMU(Mavlink *mavlink) : MavlinkStream(mavlink) {}
|
||||
|
||||
uORB::Subscription _vehicle_imu_sub{ORB_ID(vehicle_imu), 0};
|
||||
uORB::Subscription _sensor_mag_sub{ORB_ID(sensor_mag), 0};
|
||||
|
||||
bool send() override
|
||||
{
|
||||
if (_raw_imu_sub.updated() || _raw_mag_sub.updated()) {
|
||||
if (_vehicle_imu_sub.updated() || _sensor_mag_sub.updated()) {
|
||||
mavlink_scaled_imu_t msg{};
|
||||
|
||||
vehicle_imu_s imu{};
|
||||
_raw_imu_sub.copy(&imu);
|
||||
vehicle_imu_s imu;
|
||||
|
||||
sensor_mag_s sensor_mag{};
|
||||
_raw_mag_sub.copy(&sensor_mag);
|
||||
if (_vehicle_imu_sub.copy(&imu)) {
|
||||
msg.time_boot_ms = imu.timestamp / 1000;
|
||||
|
||||
// Accelerometer in mG
|
||||
const float accel_dt_inv = 1.e6f / (float)imu.delta_velocity_dt;
|
||||
const Vector3f accel = Vector3f{imu.delta_velocity} * accel_dt_inv * 1000.0f / CONSTANTS_ONE_G;
|
||||
// Accelerometer in mG
|
||||
const float accel_dt_inv = 1.e6f / (float)imu.delta_velocity_dt;
|
||||
const Vector3f accel = Vector3f{imu.delta_velocity} * accel_dt_inv * 1000.0f / CONSTANTS_ONE_G;
|
||||
msg.xacc = (int16_t)accel(0);
|
||||
msg.yacc = (int16_t)accel(1);
|
||||
msg.zacc = (int16_t)accel(2);
|
||||
|
||||
const float gyro_dt_inv = 1.e6f / (float)imu.delta_velocity_dt;
|
||||
const Vector3f gyro = Vector3f{imu.delta_angle} * gyro_dt_inv * 1000.0f;
|
||||
// Gyroscope in mrad/s
|
||||
const float gyro_dt_inv = 1.e6f / (float)imu.delta_velocity_dt;
|
||||
const Vector3f gyro = Vector3f{imu.delta_angle} * gyro_dt_inv * 1000.0f;
|
||||
msg.xgyro = gyro(0);
|
||||
msg.ygyro = gyro(1);
|
||||
msg.zgyro = gyro(2);
|
||||
}
|
||||
|
||||
send_mavlink_message(imu.timestamp / 1000, accel, gyro, sensor_mag);
|
||||
sensor_mag_s sensor_mag;
|
||||
|
||||
if (_sensor_mag_sub.copy(&sensor_mag)) {
|
||||
if (msg.time_boot_ms == 0) {
|
||||
msg.time_boot_ms = sensor_mag.timestamp / 1000;
|
||||
}
|
||||
|
||||
msg.xmag = sensor_mag.x * 1000.0f; // Gauss -> MilliGauss
|
||||
msg.ymag = sensor_mag.y * 1000.0f; // Gauss -> MilliGauss
|
||||
msg.zmag = sensor_mag.z * 1000.0f; // Gauss -> MilliGauss
|
||||
msg.temperature = sensor_mag.temperature;
|
||||
}
|
||||
|
||||
mavlink_msg_scaled_imu_send_struct(_mavlink->get_channel(), &msg);
|
||||
return true;
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
virtual void send_mavlink_message(uint32_t time_boot_ms, const Vector3f &sensor_accel, const Vector3f &gyro,
|
||||
sensor_mag_s &sensor_mag) = 0;
|
||||
|
||||
private:
|
||||
uORB::Subscription _raw_imu_sub;
|
||||
uORB::Subscription _raw_mag_sub;
|
||||
|
||||
// do not allow to copy this class
|
||||
MavlinkStreamScaledIMUBase(MavlinkStreamScaledIMUBase &) = delete;
|
||||
MavlinkStreamScaledIMUBase &operator = (const MavlinkStreamScaledIMUBase &) = delete;
|
||||
};
|
||||
|
||||
template <int N, typename Derived, uint16_t MSG_ID_SCALED_IMU, unsigned MSG_ID_SCALED_IMU_LEN, typename MavlinkMsg>
|
||||
class MavlinkStreamScaledIMUTemplate : public MavlinkStreamScaledIMUBase
|
||||
{
|
||||
public:
|
||||
const char *get_name() const override
|
||||
{
|
||||
return get_name_static();
|
||||
}
|
||||
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
return MSG_NAMES_SCALED_IMU[N];
|
||||
}
|
||||
|
||||
uint16_t get_id() override
|
||||
{
|
||||
return get_id_static();
|
||||
}
|
||||
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MSG_ID_SCALED_IMU;
|
||||
}
|
||||
|
||||
unsigned get_size() override
|
||||
{
|
||||
return MSG_ID_SCALED_IMU_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES;
|
||||
}
|
||||
|
||||
static MavlinkStream *new_instance(Mavlink *mavlink)
|
||||
{
|
||||
return new Derived(mavlink);
|
||||
}
|
||||
|
||||
private:
|
||||
typedef void (*SendMavlinkHandler)(mavlink_channel_t, const MavlinkMsg *);
|
||||
SendMavlinkHandler _send_mavlink;
|
||||
|
||||
protected:
|
||||
explicit MavlinkStreamScaledIMUTemplate(Mavlink *mavlink,
|
||||
SendMavlinkHandler handler) : MavlinkStreamScaledIMUBase(mavlink, N),
|
||||
_send_mavlink(handler)
|
||||
{}
|
||||
|
||||
void send_mavlink_message(uint32_t time_boot_ms, const Vector3f &accel, const Vector3f &gyro,
|
||||
sensor_mag_s &sensor_mag) override
|
||||
{
|
||||
MavlinkMsg msg{};
|
||||
msg.time_boot_ms = time_boot_ms;
|
||||
msg.xacc = (int16_t)accel(0);
|
||||
msg.yacc = (int16_t)accel(1);
|
||||
msg.zacc = (int16_t)accel(2);
|
||||
msg.xgyro = gyro(0);
|
||||
msg.ygyro = gyro(1);
|
||||
msg.zgyro = gyro(2);
|
||||
msg.xmag = sensor_mag.x * 1000.0f; // Gauss -> MilliGauss
|
||||
msg.ymag = sensor_mag.y * 1000.0f; // Gauss -> MilliGauss
|
||||
msg.zmag = sensor_mag.z * 1000.0f; // Gauss -> MilliGauss
|
||||
msg.temperature = sensor_mag.temperature;
|
||||
|
||||
_send_mavlink(_mavlink->get_channel(), &msg);
|
||||
}
|
||||
};
|
||||
|
||||
template <int N> struct MavlinkStreamScaledIMU {};
|
||||
|
||||
template <>
|
||||
class MavlinkStreamScaledIMU<0> : public
|
||||
MavlinkStreamScaledIMUTemplate<0, MavlinkStreamScaledIMU<0>, MAVLINK_MSG_ID_SCALED_IMU, MAVLINK_MSG_ID_SCALED_IMU_LEN, mavlink_scaled_imu_t>
|
||||
{
|
||||
public:
|
||||
typedef MavlinkStreamScaledIMUTemplate<0, MavlinkStreamScaledIMU<0>, MAVLINK_MSG_ID_SCALED_IMU, MAVLINK_MSG_ID_SCALED_IMU_LEN, mavlink_scaled_imu_t>
|
||||
Base;
|
||||
|
||||
explicit MavlinkStreamScaledIMU(Mavlink *mavlink) : Base(mavlink, mavlink_msg_scaled_imu_send_struct)
|
||||
{}
|
||||
};
|
||||
|
||||
template <>
|
||||
class MavlinkStreamScaledIMU<1> : public
|
||||
MavlinkStreamScaledIMUTemplate<1, MavlinkStreamScaledIMU<1>, MAVLINK_MSG_ID_SCALED_IMU2, MAVLINK_MSG_ID_SCALED_IMU2_LEN, mavlink_scaled_imu2_t>
|
||||
{
|
||||
public:
|
||||
typedef MavlinkStreamScaledIMUTemplate<1, MavlinkStreamScaledIMU<1>, MAVLINK_MSG_ID_SCALED_IMU2, MAVLINK_MSG_ID_SCALED_IMU2_LEN, mavlink_scaled_imu2_t>
|
||||
Base;
|
||||
|
||||
explicit MavlinkStreamScaledIMU(Mavlink *mavlink) : Base(mavlink, mavlink_msg_scaled_imu2_send_struct)
|
||||
{}
|
||||
};
|
||||
|
||||
template <>
|
||||
class MavlinkStreamScaledIMU<2> : public
|
||||
MavlinkStreamScaledIMUTemplate<2, MavlinkStreamScaledIMU<2>, MAVLINK_MSG_ID_SCALED_IMU3, MAVLINK_MSG_ID_SCALED_IMU3_LEN, mavlink_scaled_imu3_t>
|
||||
{
|
||||
public:
|
||||
typedef MavlinkStreamScaledIMUTemplate<2, MavlinkStreamScaledIMU<2>, MAVLINK_MSG_ID_SCALED_IMU3, MAVLINK_MSG_ID_SCALED_IMU3_LEN, mavlink_scaled_imu3_t>
|
||||
Base;
|
||||
|
||||
explicit MavlinkStreamScaledIMU(Mavlink *mavlink) : Base(mavlink, mavlink_msg_scaled_imu3_send_struct)
|
||||
{}
|
||||
};
|
||||
|
||||
|
||||
#endif /* SCALED_IMU_HPP */
|
||||
|
||||
@@ -0,0 +1,114 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* 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 SCALED_IMU2_HPP
|
||||
#define SCALED_IMU2_HPP
|
||||
|
||||
#include <lib/ecl/geo/geo.h>
|
||||
#include <lib/matrix/matrix/math.hpp>
|
||||
|
||||
#include <uORB/topics/sensor_mag.h>
|
||||
#include <uORB/topics/vehicle_imu.h>
|
||||
|
||||
class MavlinkStreamScaledIMU2 : public MavlinkStream
|
||||
{
|
||||
public:
|
||||
static MavlinkStream *new_instance(Mavlink *mavlink) { return new MavlinkStreamScaledIMU2(mavlink); }
|
||||
|
||||
static constexpr const char *get_name_static() { return "SCALED_IMU2"; }
|
||||
static constexpr uint16_t get_id_static() { return MAVLINK_MSG_ID_SCALED_IMU2; }
|
||||
|
||||
const char *get_name() const override { return get_name_static(); }
|
||||
uint16_t get_id() override { return get_id_static(); }
|
||||
|
||||
unsigned get_size() override
|
||||
{
|
||||
if (_vehicle_imu_sub.advertised() || _sensor_mag_sub.advertised()) {
|
||||
return MAVLINK_MSG_ID_SCALED_IMU2_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
private:
|
||||
explicit MavlinkStreamScaledIMU2(Mavlink *mavlink) : MavlinkStream(mavlink) {}
|
||||
|
||||
uORB::Subscription _vehicle_imu_sub{ORB_ID(vehicle_imu), 1};
|
||||
uORB::Subscription _sensor_mag_sub{ORB_ID(sensor_mag), 1};
|
||||
|
||||
bool send() override
|
||||
{
|
||||
if (_vehicle_imu_sub.updated() || _sensor_mag_sub.updated()) {
|
||||
mavlink_scaled_imu2_t msg{};
|
||||
|
||||
vehicle_imu_s imu;
|
||||
|
||||
if (_vehicle_imu_sub.copy(&imu)) {
|
||||
msg.time_boot_ms = imu.timestamp / 1000;
|
||||
|
||||
// Accelerometer in mG
|
||||
const float accel_dt_inv = 1.e6f / (float)imu.delta_velocity_dt;
|
||||
const Vector3f accel = Vector3f{imu.delta_velocity} * accel_dt_inv * 1000.0f / CONSTANTS_ONE_G;
|
||||
msg.xacc = (int16_t)accel(0);
|
||||
msg.yacc = (int16_t)accel(1);
|
||||
msg.zacc = (int16_t)accel(2);
|
||||
|
||||
// Gyroscope in mrad/s
|
||||
const float gyro_dt_inv = 1.e6f / (float)imu.delta_velocity_dt;
|
||||
const Vector3f gyro = Vector3f{imu.delta_angle} * gyro_dt_inv * 1000.0f;
|
||||
msg.xgyro = gyro(0);
|
||||
msg.ygyro = gyro(1);
|
||||
msg.zgyro = gyro(2);
|
||||
}
|
||||
|
||||
sensor_mag_s sensor_mag;
|
||||
|
||||
if (_sensor_mag_sub.copy(&sensor_mag)) {
|
||||
if (msg.time_boot_ms == 0) {
|
||||
msg.time_boot_ms = sensor_mag.timestamp / 1000;
|
||||
}
|
||||
|
||||
msg.xmag = sensor_mag.x * 1000.0f; // Gauss -> MilliGauss
|
||||
msg.ymag = sensor_mag.y * 1000.0f; // Gauss -> MilliGauss
|
||||
msg.zmag = sensor_mag.z * 1000.0f; // Gauss -> MilliGauss
|
||||
msg.temperature = sensor_mag.temperature;
|
||||
}
|
||||
|
||||
mavlink_msg_scaled_imu2_send_struct(_mavlink->get_channel(), &msg);
|
||||
return true;
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
};
|
||||
#endif /* SCALED_IMU2_HPP */
|
||||
@@ -0,0 +1,114 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* 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 SCALED_IMU3_HPP
|
||||
#define SCALED_IMU3_HPP
|
||||
|
||||
#include <lib/ecl/geo/geo.h>
|
||||
#include <lib/matrix/matrix/math.hpp>
|
||||
|
||||
#include <uORB/topics/sensor_mag.h>
|
||||
#include <uORB/topics/vehicle_imu.h>
|
||||
|
||||
class MavlinkStreamScaledIMU3 : public MavlinkStream
|
||||
{
|
||||
public:
|
||||
static MavlinkStream *new_instance(Mavlink *mavlink) { return new MavlinkStreamScaledIMU3(mavlink); }
|
||||
|
||||
static constexpr const char *get_name_static() { return "SCALED_IMU3"; }
|
||||
static constexpr uint16_t get_id_static() { return MAVLINK_MSG_ID_SCALED_IMU3; }
|
||||
|
||||
const char *get_name() const override { return get_name_static(); }
|
||||
uint16_t get_id() override { return get_id_static(); }
|
||||
|
||||
unsigned get_size() override
|
||||
{
|
||||
if (_vehicle_imu_sub.advertised() || _sensor_mag_sub.advertised()) {
|
||||
return MAVLINK_MSG_ID_SCALED_IMU3_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
private:
|
||||
explicit MavlinkStreamScaledIMU3(Mavlink *mavlink) : MavlinkStream(mavlink) {}
|
||||
|
||||
uORB::Subscription _vehicle_imu_sub{ORB_ID(vehicle_imu), 2};
|
||||
uORB::Subscription _sensor_mag_sub{ORB_ID(sensor_mag), 2};
|
||||
|
||||
bool send() override
|
||||
{
|
||||
if (_vehicle_imu_sub.updated() || _sensor_mag_sub.updated()) {
|
||||
mavlink_scaled_imu3_t msg{};
|
||||
|
||||
vehicle_imu_s imu;
|
||||
|
||||
if (_vehicle_imu_sub.copy(&imu)) {
|
||||
msg.time_boot_ms = imu.timestamp / 1000;
|
||||
|
||||
// Accelerometer in mG
|
||||
const float accel_dt_inv = 1.e6f / (float)imu.delta_velocity_dt;
|
||||
const Vector3f accel = Vector3f{imu.delta_velocity} * accel_dt_inv * 1000.0f / CONSTANTS_ONE_G;
|
||||
msg.xacc = (int16_t)accel(0);
|
||||
msg.yacc = (int16_t)accel(1);
|
||||
msg.zacc = (int16_t)accel(2);
|
||||
|
||||
// Gyroscope in mrad/s
|
||||
const float gyro_dt_inv = 1.e6f / (float)imu.delta_velocity_dt;
|
||||
const Vector3f gyro = Vector3f{imu.delta_angle} * gyro_dt_inv * 1000.0f;
|
||||
msg.xgyro = gyro(0);
|
||||
msg.ygyro = gyro(1);
|
||||
msg.zgyro = gyro(2);
|
||||
}
|
||||
|
||||
sensor_mag_s sensor_mag;
|
||||
|
||||
if (_sensor_mag_sub.copy(&sensor_mag)) {
|
||||
if (msg.time_boot_ms == 0) {
|
||||
msg.time_boot_ms = sensor_mag.timestamp / 1000;
|
||||
}
|
||||
|
||||
msg.xmag = sensor_mag.x * 1000.0f; // Gauss -> MilliGauss
|
||||
msg.ymag = sensor_mag.y * 1000.0f; // Gauss -> MilliGauss
|
||||
msg.zmag = sensor_mag.z * 1000.0f; // Gauss -> MilliGauss
|
||||
msg.temperature = sensor_mag.temperature;
|
||||
}
|
||||
|
||||
mavlink_msg_scaled_imu3_send_struct(_mavlink->get_channel(), &msg);
|
||||
return true;
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
};
|
||||
#endif /* SCALED_IMU3_HPP */
|
||||
Reference in New Issue
Block a user