mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
mavlink: move OPTICAL_FLOW to streams hpp
Signed-off-by: Antonio Sanjurjo Cortés <74329840+antonio-sc66@users.noreply.github.com>
This commit is contained in:
parent
5f0ecc893e
commit
0bf622e211
@ -73,7 +73,6 @@
|
||||
#include <uORB/topics/home_position.h>
|
||||
#include <uORB/topics/input_rc.h>
|
||||
#include <uORB/topics/manual_control_setpoint.h>
|
||||
#include <uORB/topics/optical_flow.h>
|
||||
#include <uORB/topics/position_controller_status.h>
|
||||
#include <uORB/topics/position_setpoint_triplet.h>
|
||||
#include <uORB/topics/sensor_baro.h>
|
||||
@ -119,6 +118,7 @@ using matrix::wrap_2pi;
|
||||
#include "streams/HIL_STATE_QUATERNION.hpp"
|
||||
#include "streams/MOUNT_ORIENTATION.hpp"
|
||||
#include "streams/OBSTACLE_DISTANCE.hpp"
|
||||
#include "streams/OPTICAL_FLOW.hpp"
|
||||
#include "streams/ORBIT_EXECUTION_STATUS.hpp"
|
||||
#include "streams/PING.hpp"
|
||||
#include "streams/PROTOCOL_VERSION.hpp"
|
||||
@ -4062,80 +4062,6 @@ protected:
|
||||
}
|
||||
};
|
||||
|
||||
class MavlinkStreamOpticalFlowRad : public MavlinkStream
|
||||
{
|
||||
public:
|
||||
const char *get_name() const override
|
||||
{
|
||||
return MavlinkStreamOpticalFlowRad::get_name_static();
|
||||
}
|
||||
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
return "OPTICAL_FLOW_RAD";
|
||||
}
|
||||
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_OPTICAL_FLOW_RAD;
|
||||
}
|
||||
|
||||
uint16_t get_id() override
|
||||
{
|
||||
return get_id_static();
|
||||
}
|
||||
|
||||
static MavlinkStream *new_instance(Mavlink *mavlink)
|
||||
{
|
||||
return new MavlinkStreamOpticalFlowRad(mavlink);
|
||||
}
|
||||
|
||||
unsigned get_size() override
|
||||
{
|
||||
return _flow_sub.advertised() ? (MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) : 0;
|
||||
}
|
||||
|
||||
private:
|
||||
uORB::Subscription _flow_sub{ORB_ID(optical_flow)};
|
||||
|
||||
/* do not allow top copying this class */
|
||||
MavlinkStreamOpticalFlowRad(MavlinkStreamOpticalFlowRad &) = delete;
|
||||
MavlinkStreamOpticalFlowRad &operator = (const MavlinkStreamOpticalFlowRad &) = delete;
|
||||
|
||||
protected:
|
||||
explicit MavlinkStreamOpticalFlowRad(Mavlink *mavlink) : MavlinkStream(mavlink)
|
||||
{}
|
||||
|
||||
bool send() override
|
||||
{
|
||||
optical_flow_s flow;
|
||||
|
||||
if (_flow_sub.update(&flow)) {
|
||||
mavlink_optical_flow_rad_t msg{};
|
||||
|
||||
msg.time_usec = flow.timestamp;
|
||||
msg.sensor_id = flow.sensor_id;
|
||||
msg.integrated_x = flow.pixel_flow_x_integral;
|
||||
msg.integrated_y = flow.pixel_flow_y_integral;
|
||||
msg.integrated_xgyro = flow.gyro_x_rate_integral;
|
||||
msg.integrated_ygyro = flow.gyro_y_rate_integral;
|
||||
msg.integrated_zgyro = flow.gyro_z_rate_integral;
|
||||
msg.distance = flow.ground_distance_m;
|
||||
msg.quality = flow.quality;
|
||||
msg.integration_time_us = flow.integration_timespan;
|
||||
msg.sensor_id = flow.sensor_id;
|
||||
msg.time_delta_distance_us = flow.time_since_last_sonar_update;
|
||||
msg.temperature = flow.gyro_temperature;
|
||||
|
||||
mavlink_msg_optical_flow_rad_send_struct(_mavlink->get_channel(), &msg);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
};
|
||||
|
||||
class MavlinkStreamNavControllerOutput : public MavlinkStream
|
||||
{
|
||||
public:
|
||||
@ -4325,7 +4251,9 @@ static const StreamListItem streams_list[] = {
|
||||
create_stream_list_item<MavlinkStreamRCChannels>(),
|
||||
create_stream_list_item<MavlinkStreamManualControl>(),
|
||||
create_stream_list_item<MavlinkStreamTrajectoryRepresentationWaypoints>(),
|
||||
#if defined(OPTICAL_FLOW_HPP)
|
||||
create_stream_list_item<MavlinkStreamOpticalFlowRad>(),
|
||||
#endif // OPTICAL_FLOW_HPP
|
||||
create_stream_list_item<MavlinkStreamActuatorControlTarget<0> >(),
|
||||
create_stream_list_item<MavlinkStreamActuatorControlTarget<1> >(),
|
||||
#if defined(NAMED_VALUE_FLOAT_HPP)
|
||||
|
||||
113
src/modules/mavlink/streams/OPTICAL_FLOW.hpp
Normal file
113
src/modules/mavlink/streams/OPTICAL_FLOW.hpp
Normal file
@ -0,0 +1,113 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2020 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 OPTICAL_FLOW_HPP
|
||||
#define OPTICAL_FLOW_HPP
|
||||
|
||||
#include <uORB/topics/optical_flow.h>
|
||||
|
||||
class MavlinkStreamOpticalFlowRad : public MavlinkStream
|
||||
{
|
||||
public:
|
||||
const char *get_name() const override
|
||||
{
|
||||
return MavlinkStreamOpticalFlowRad::get_name_static();
|
||||
}
|
||||
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
return "OPTICAL_FLOW_RAD";
|
||||
}
|
||||
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_OPTICAL_FLOW_RAD;
|
||||
}
|
||||
|
||||
uint16_t get_id() override
|
||||
{
|
||||
return get_id_static();
|
||||
}
|
||||
|
||||
static MavlinkStream *new_instance(Mavlink *mavlink)
|
||||
{
|
||||
return new MavlinkStreamOpticalFlowRad(mavlink);
|
||||
}
|
||||
|
||||
unsigned get_size() override
|
||||
{
|
||||
return _flow_sub.advertised() ? (MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) : 0;
|
||||
}
|
||||
|
||||
private:
|
||||
uORB::Subscription _flow_sub{ORB_ID(optical_flow)};
|
||||
|
||||
/* do not allow top copying this class */
|
||||
MavlinkStreamOpticalFlowRad(MavlinkStreamOpticalFlowRad &) = delete;
|
||||
MavlinkStreamOpticalFlowRad &operator = (const MavlinkStreamOpticalFlowRad &) = delete;
|
||||
|
||||
protected:
|
||||
explicit MavlinkStreamOpticalFlowRad(Mavlink *mavlink) : MavlinkStream(mavlink)
|
||||
{}
|
||||
|
||||
bool send() override
|
||||
{
|
||||
optical_flow_s flow;
|
||||
|
||||
if (_flow_sub.update(&flow)) {
|
||||
mavlink_optical_flow_rad_t msg{};
|
||||
|
||||
msg.time_usec = flow.timestamp;
|
||||
msg.sensor_id = flow.sensor_id;
|
||||
msg.integrated_x = flow.pixel_flow_x_integral;
|
||||
msg.integrated_y = flow.pixel_flow_y_integral;
|
||||
msg.integrated_xgyro = flow.gyro_x_rate_integral;
|
||||
msg.integrated_ygyro = flow.gyro_y_rate_integral;
|
||||
msg.integrated_zgyro = flow.gyro_z_rate_integral;
|
||||
msg.distance = flow.ground_distance_m;
|
||||
msg.quality = flow.quality;
|
||||
msg.integration_time_us = flow.integration_timespan;
|
||||
msg.sensor_id = flow.sensor_id;
|
||||
msg.time_delta_distance_us = flow.time_since_last_sonar_update;
|
||||
msg.temperature = flow.gyro_temperature;
|
||||
|
||||
mavlink_msg_optical_flow_rad_send_struct(_mavlink->get_channel(), &msg);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
};
|
||||
|
||||
#endif // OPTICAL_FLOW_HPP
|
||||
Loading…
x
Reference in New Issue
Block a user