mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-02 03:49:12 +08:00
mavlink: move MANUAL_CONTROL to separate streams header
This commit is contained in:
committed by
Lorenz Meier
parent
629d03b684
commit
48be6962d1
@@ -71,8 +71,6 @@
|
|||||||
#include <uORB/topics/geofence_result.h>
|
#include <uORB/topics/geofence_result.h>
|
||||||
#include <uORB/topics/home_position.h>
|
#include <uORB/topics/home_position.h>
|
||||||
#include <uORB/topics/input_rc.h>
|
#include <uORB/topics/input_rc.h>
|
||||||
#include <uORB/topics/manual_control_setpoint.h>
|
|
||||||
#include <uORB/topics/manual_control_switches.h>
|
|
||||||
#include <uORB/topics/position_setpoint_triplet.h>
|
#include <uORB/topics/position_setpoint_triplet.h>
|
||||||
#include <uORB/topics/sensor_baro.h>
|
#include <uORB/topics/sensor_baro.h>
|
||||||
#include <uORB/topics/sensor_gps.h>
|
#include <uORB/topics/sensor_gps.h>
|
||||||
@@ -117,6 +115,7 @@ using matrix::wrap_2pi;
|
|||||||
#include "streams/GPS_STATUS.hpp"
|
#include "streams/GPS_STATUS.hpp"
|
||||||
#include "streams/HIGH_LATENCY2.hpp"
|
#include "streams/HIGH_LATENCY2.hpp"
|
||||||
#include "streams/HIL_STATE_QUATERNION.hpp"
|
#include "streams/HIL_STATE_QUATERNION.hpp"
|
||||||
|
#include "streams/MANUAL_CONTROL.hpp"
|
||||||
#include "streams/MOUNT_ORIENTATION.hpp"
|
#include "streams/MOUNT_ORIENTATION.hpp"
|
||||||
#include "streams/NAV_CONTROLLER_OUTPUT.hpp"
|
#include "streams/NAV_CONTROLLER_OUTPUT.hpp"
|
||||||
#include "streams/OBSTACLE_DISTANCE.hpp"
|
#include "streams/OBSTACLE_DISTANCE.hpp"
|
||||||
@@ -3584,89 +3583,6 @@ protected:
|
|||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
class MavlinkStreamManualControl : public MavlinkStream
|
|
||||||
{
|
|
||||||
public:
|
|
||||||
const char *get_name() const override
|
|
||||||
{
|
|
||||||
return MavlinkStreamManualControl::get_name_static();
|
|
||||||
}
|
|
||||||
|
|
||||||
static constexpr const char *get_name_static()
|
|
||||||
{
|
|
||||||
return "MANUAL_CONTROL";
|
|
||||||
}
|
|
||||||
|
|
||||||
static constexpr uint16_t get_id_static()
|
|
||||||
{
|
|
||||||
return MAVLINK_MSG_ID_MANUAL_CONTROL;
|
|
||||||
}
|
|
||||||
|
|
||||||
uint16_t get_id() override
|
|
||||||
{
|
|
||||||
return get_id_static();
|
|
||||||
}
|
|
||||||
|
|
||||||
static MavlinkStream *new_instance(Mavlink *mavlink)
|
|
||||||
{
|
|
||||||
return new MavlinkStreamManualControl(mavlink);
|
|
||||||
}
|
|
||||||
|
|
||||||
unsigned get_size() override
|
|
||||||
{
|
|
||||||
return _manual_control_setpoint_sub.advertised() ?
|
|
||||||
(MAVLINK_MSG_ID_MANUAL_CONTROL_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) : 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
private:
|
|
||||||
uORB::Subscription _manual_control_setpoint_sub{ORB_ID(manual_control_setpoint)};
|
|
||||||
uORB::Subscription _manual_control_switches_sub{ORB_ID(manual_control_switches)};
|
|
||||||
|
|
||||||
/* do not allow top copying this class */
|
|
||||||
MavlinkStreamManualControl(MavlinkStreamManualControl &) = delete;
|
|
||||||
MavlinkStreamManualControl &operator = (const MavlinkStreamManualControl &) = delete;
|
|
||||||
|
|
||||||
protected:
|
|
||||||
explicit MavlinkStreamManualControl(Mavlink *mavlink) : MavlinkStream(mavlink)
|
|
||||||
{}
|
|
||||||
|
|
||||||
bool send() override
|
|
||||||
{
|
|
||||||
manual_control_setpoint_s manual_control_setpoint;
|
|
||||||
|
|
||||||
if (_manual_control_setpoint_sub.update(&manual_control_setpoint)) {
|
|
||||||
mavlink_manual_control_t msg{};
|
|
||||||
|
|
||||||
msg.target = mavlink_system.sysid;
|
|
||||||
msg.x = manual_control_setpoint.x * 1000;
|
|
||||||
msg.y = manual_control_setpoint.y * 1000;
|
|
||||||
msg.z = manual_control_setpoint.z * 1000;
|
|
||||||
msg.r = manual_control_setpoint.r * 1000;
|
|
||||||
|
|
||||||
manual_control_switches_s manual_control_switches{};
|
|
||||||
|
|
||||||
if (_manual_control_switches_sub.copy(&manual_control_switches)) {
|
|
||||||
unsigned shift = 2;
|
|
||||||
msg.buttons = 0;
|
|
||||||
msg.buttons |= (manual_control_switches.mode_switch << (shift * 0));
|
|
||||||
msg.buttons |= (manual_control_switches.return_switch << (shift * 1));
|
|
||||||
msg.buttons |= (manual_control_switches.posctl_switch << (shift * 2));
|
|
||||||
msg.buttons |= (manual_control_switches.loiter_switch << (shift * 3));
|
|
||||||
msg.buttons |= (manual_control_switches.acro_switch << (shift * 4));
|
|
||||||
msg.buttons |= (manual_control_switches.offboard_switch << (shift * 5));
|
|
||||||
msg.buttons |= (manual_control_switches.kill_switch << (shift * 6));
|
|
||||||
}
|
|
||||||
|
|
||||||
mavlink_msg_manual_control_send_struct(_mavlink->get_channel(), &msg);
|
|
||||||
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
};
|
|
||||||
|
|
||||||
class MavlinkStreamCameraCapture : public MavlinkStream
|
class MavlinkStreamCameraCapture : public MavlinkStream
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
@@ -3784,7 +3700,9 @@ static const StreamListItem streams_list[] = {
|
|||||||
create_stream_list_item<MavlinkStreamAttitudeTarget>(),
|
create_stream_list_item<MavlinkStreamAttitudeTarget>(),
|
||||||
#endif // ATTITUDE_TARGET_HPP
|
#endif // ATTITUDE_TARGET_HPP
|
||||||
create_stream_list_item<MavlinkStreamRCChannels>(),
|
create_stream_list_item<MavlinkStreamRCChannels>(),
|
||||||
|
#if defined(MANUAL_CONTROL_HPP)
|
||||||
create_stream_list_item<MavlinkStreamManualControl>(),
|
create_stream_list_item<MavlinkStreamManualControl>(),
|
||||||
|
#endif // MANUAL_CONTROL_HPP
|
||||||
#if defined(TRAJECTORY_REPRESENTATION_WAYPOINTS_HPP)
|
#if defined(TRAJECTORY_REPRESENTATION_WAYPOINTS_HPP)
|
||||||
create_stream_list_item<MavlinkStreamTrajectoryRepresentationWaypoints>(),
|
create_stream_list_item<MavlinkStreamTrajectoryRepresentationWaypoints>(),
|
||||||
#endif // TRAJECTORY_REPRESENTATION_WAYPOINTS_HPP
|
#endif // TRAJECTORY_REPRESENTATION_WAYPOINTS_HPP
|
||||||
|
|||||||
@@ -0,0 +1,99 @@
|
|||||||
|
/****************************************************************************
|
||||||
|
*
|
||||||
|
* 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 MANUAL_CONTROL_HPP
|
||||||
|
#define MANUAL_CONTROL_HPP
|
||||||
|
|
||||||
|
#include <uORB/topics/manual_control_setpoint.h>
|
||||||
|
#include <uORB/topics/manual_control_switches.h>
|
||||||
|
|
||||||
|
class MavlinkStreamManualControl : public MavlinkStream
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
static MavlinkStream *new_instance(Mavlink *mavlink) { return new MavlinkStreamManualControl(mavlink); }
|
||||||
|
|
||||||
|
static constexpr const char *get_name_static() { return "MANUAL_CONTROL"; }
|
||||||
|
static constexpr uint16_t get_id_static() { return MAVLINK_MSG_ID_MANUAL_CONTROL; }
|
||||||
|
|
||||||
|
const char *get_name() const override { return get_name_static(); }
|
||||||
|
uint16_t get_id() override { return get_id_static(); }
|
||||||
|
|
||||||
|
unsigned get_size() override
|
||||||
|
{
|
||||||
|
return _manual_control_setpoint_sub.advertised() ? (MAVLINK_MSG_ID_MANUAL_CONTROL_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) :
|
||||||
|
0;
|
||||||
|
}
|
||||||
|
|
||||||
|
private:
|
||||||
|
explicit MavlinkStreamManualControl(Mavlink *mavlink) : MavlinkStream(mavlink) {}
|
||||||
|
|
||||||
|
uORB::Subscription _manual_control_setpoint_sub{ORB_ID(manual_control_setpoint)};
|
||||||
|
uORB::Subscription _manual_control_switches_sub{ORB_ID(manual_control_switches)};
|
||||||
|
|
||||||
|
bool send() override
|
||||||
|
{
|
||||||
|
manual_control_setpoint_s manual_control_setpoint;
|
||||||
|
|
||||||
|
if (_manual_control_setpoint_sub.update(&manual_control_setpoint)) {
|
||||||
|
mavlink_manual_control_t msg{};
|
||||||
|
|
||||||
|
msg.target = mavlink_system.sysid;
|
||||||
|
msg.x = manual_control_setpoint.x * 1000;
|
||||||
|
msg.y = manual_control_setpoint.y * 1000;
|
||||||
|
msg.z = manual_control_setpoint.z * 1000;
|
||||||
|
msg.r = manual_control_setpoint.r * 1000;
|
||||||
|
|
||||||
|
manual_control_switches_s manual_control_switches{};
|
||||||
|
|
||||||
|
if (_manual_control_switches_sub.copy(&manual_control_switches)) {
|
||||||
|
unsigned shift = 2;
|
||||||
|
msg.buttons = 0;
|
||||||
|
msg.buttons |= (manual_control_switches.mode_switch << (shift * 0));
|
||||||
|
msg.buttons |= (manual_control_switches.return_switch << (shift * 1));
|
||||||
|
msg.buttons |= (manual_control_switches.posctl_switch << (shift * 2));
|
||||||
|
msg.buttons |= (manual_control_switches.loiter_switch << (shift * 3));
|
||||||
|
msg.buttons |= (manual_control_switches.acro_switch << (shift * 4));
|
||||||
|
msg.buttons |= (manual_control_switches.offboard_switch << (shift * 5));
|
||||||
|
msg.buttons |= (manual_control_switches.kill_switch << (shift * 6));
|
||||||
|
}
|
||||||
|
|
||||||
|
mavlink_msg_manual_control_send_struct(_mavlink->get_channel(), &msg);
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif // MANUAL_CONTROL
|
||||||
Reference in New Issue
Block a user