forked from Archive/PX4-Autopilot
Merge branch 'mavlink_command' of github.com:PX4/Firmware
This commit is contained in:
commit
8e0e0c164a
|
@ -0,0 +1,73 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2014 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_commands.cpp
|
||||
* Mavlink commands stream implementation.
|
||||
*
|
||||
* @author Anton Babushkin <anton.babushkin@me.com>
|
||||
*/
|
||||
|
||||
#include "mavlink_commands.h"
|
||||
|
||||
MavlinkCommandsStream::MavlinkCommandsStream(Mavlink *mavlink, mavlink_channel_t channel) : _channel(channel)
|
||||
{
|
||||
_cmd_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_command));
|
||||
_cmd = (struct vehicle_command_s *)_cmd_sub->get_data();
|
||||
}
|
||||
|
||||
MavlinkCommandsStream::~MavlinkCommandsStream()
|
||||
{
|
||||
}
|
||||
|
||||
void
|
||||
MavlinkCommandsStream::update(const hrt_abstime t)
|
||||
{
|
||||
if (_cmd_sub->update(t)) {
|
||||
/* only send commands for other systems/components */
|
||||
if (_cmd->target_system != mavlink_system.sysid || _cmd->target_component != mavlink_system.compid) {
|
||||
mavlink_msg_command_long_send(_channel,
|
||||
_cmd->target_system,
|
||||
_cmd->target_component,
|
||||
_cmd->command,
|
||||
_cmd->confirmation,
|
||||
_cmd->param1,
|
||||
_cmd->param2,
|
||||
_cmd->param3,
|
||||
_cmd->param4,
|
||||
_cmd->param5,
|
||||
_cmd->param6,
|
||||
_cmd->param7);
|
||||
}
|
||||
}
|
||||
}
|
|
@ -0,0 +1,65 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2014 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_commands.h
|
||||
* Mavlink commands stream definition.
|
||||
*
|
||||
* @author Anton Babushkin <anton.babushkin@me.com>
|
||||
*/
|
||||
|
||||
#ifndef MAVLINK_COMMANDS_H_
|
||||
#define MAVLINK_COMMANDS_H_
|
||||
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/vehicle_command.h>
|
||||
|
||||
class Mavlink;
|
||||
class MavlinkCommansStream;
|
||||
|
||||
#include "mavlink_main.h"
|
||||
|
||||
class MavlinkCommandsStream
|
||||
{
|
||||
private:
|
||||
MavlinkOrbSubscription *_cmd_sub;
|
||||
struct vehicle_command_s *_cmd;
|
||||
mavlink_channel_t _channel;
|
||||
|
||||
public:
|
||||
MavlinkCommandsStream(Mavlink *mavlink, mavlink_channel_t channel);
|
||||
~MavlinkCommandsStream();
|
||||
void update(const hrt_abstime t);
|
||||
};
|
||||
|
||||
#endif /* MAVLINK_COMMANDS_H_ */
|
|
@ -81,6 +81,7 @@
|
|||
#include "mavlink_messages.h"
|
||||
#include "mavlink_receiver.h"
|
||||
#include "mavlink_rate_limiter.h"
|
||||
#include "mavlink_commands.h"
|
||||
|
||||
/* oddly, ERROR is not defined for c++ */
|
||||
#ifdef ERROR
|
||||
|
@ -1920,6 +1921,8 @@ Mavlink::task_main(int argc, char *argv[])
|
|||
|
||||
struct vehicle_status_s *status = (struct vehicle_status_s *) status_sub->get_data();
|
||||
|
||||
MavlinkCommandsStream commands_stream(this, _channel);
|
||||
|
||||
/* add default streams depending on mode and intervals depending on datarate */
|
||||
float rate_mult = _datarate / 1000.0f;
|
||||
|
||||
|
@ -1982,6 +1985,9 @@ Mavlink::task_main(int argc, char *argv[])
|
|||
set_hil_enabled(status->hil_state == HIL_STATE_ON);
|
||||
}
|
||||
|
||||
/* update commands stream */
|
||||
commands_stream.update(t);
|
||||
|
||||
/* check for requested subscriptions */
|
||||
if (_subscribe_to_stream != nullptr) {
|
||||
if (OK == configure_stream(_subscribe_to_stream, _subscribe_to_stream_rate)) {
|
||||
|
|
|
@ -42,6 +42,7 @@ SRCS += mavlink_main.cpp \
|
|||
mavlink_orb_subscription.cpp \
|
||||
mavlink_messages.cpp \
|
||||
mavlink_stream.cpp \
|
||||
mavlink_rate_limiter.cpp
|
||||
mavlink_rate_limiter.cpp \
|
||||
mavlink_commands.cpp
|
||||
|
||||
INCLUDE_DIRS += $(MAVLINK_SRC)/include/mavlink
|
||||
|
|
Loading…
Reference in New Issue