mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-02 11:59:17 +08:00
Merged mavlink_beta2
This commit is contained in:
@@ -5,38 +5,7 @@
|
||||
|
||||
echo "Starting MAVLink on this USB console"
|
||||
|
||||
# Stop tone alarm
|
||||
tone_alarm stop
|
||||
|
||||
#
|
||||
# Check for UORB
|
||||
#
|
||||
if uorb start
|
||||
then
|
||||
echo "uORB started"
|
||||
fi
|
||||
|
||||
# Tell MAVLink that this link is "fast"
|
||||
if mavlink stop
|
||||
then
|
||||
echo "stopped other MAVLink instance"
|
||||
fi
|
||||
mavlink start -b 230400 -d /dev/ttyACM0
|
||||
|
||||
# Stop commander
|
||||
if commander stop
|
||||
then
|
||||
echo "Commander stopped"
|
||||
fi
|
||||
sleep 1
|
||||
|
||||
# Start the commander
|
||||
if commander start
|
||||
then
|
||||
echo "Commander started"
|
||||
fi
|
||||
|
||||
echo "MAVLink started, exiting shell.."
|
||||
mavlink start -r 5000 -d /dev/ttyACM0
|
||||
|
||||
# Exit shell to make it available to MAVLink
|
||||
exit
|
||||
|
||||
@@ -117,6 +117,8 @@ then
|
||||
set PWM_MAX none
|
||||
set MKBLCTRL_MODE none
|
||||
set FMU_MODE pwm
|
||||
set MAVLINK_FLAGS default
|
||||
set EXIT_ON_END no
|
||||
set MAV_TYPE none
|
||||
|
||||
#
|
||||
@@ -384,30 +386,35 @@ then
|
||||
#
|
||||
# MAVLink
|
||||
#
|
||||
set EXIT_ON_END no
|
||||
|
||||
if [ $HIL == yes ]
|
||||
if [ $MAVLINK_FLAGS == default ]
|
||||
then
|
||||
sleep 1
|
||||
mavlink start -b 230400 -d /dev/ttyACM0
|
||||
gps start
|
||||
usleep 5000
|
||||
else
|
||||
if [ $TTYS1_BUSY == yes ]
|
||||
if [ $HIL == yes ]
|
||||
then
|
||||
# Start MAVLink on ttyS0, because FMU ttyS1 pins configured as something else
|
||||
mavlink start -d /dev/ttyS0
|
||||
sleep 1
|
||||
set MAVLINK_FLAGS "-r 10000 -d /dev/ttyACM0 -m hil"
|
||||
usleep 5000
|
||||
|
||||
# Exit from nsh to free port for mavlink
|
||||
set EXIT_ON_END yes
|
||||
else
|
||||
# Start MAVLink on default port: ttyS1
|
||||
mavlink start
|
||||
usleep 5000
|
||||
# Normal mode, use baudrate 57600 (default) and data rate 1000 bytes/s
|
||||
if [ $TTYS1_BUSY == yes ]
|
||||
then
|
||||
# Start MAVLink on ttyS0, because FMU ttyS1 pins configured as something else
|
||||
set MAVLINK_FLAGS "-r 1000 -d /dev/ttyS0"
|
||||
usleep 5000
|
||||
|
||||
# Exit from nsh to free port for mavlink
|
||||
set EXIT_ON_END yes
|
||||
else
|
||||
# Start MAVLink on default port: ttyS1
|
||||
set MAVLINK_FLAGS "-r 1000"
|
||||
usleep 5000
|
||||
fi
|
||||
fi
|
||||
fi
|
||||
|
||||
mavlink start $MAVLINK_FLAGS
|
||||
usleep 5000
|
||||
|
||||
#
|
||||
# Start the datamanager
|
||||
#
|
||||
@@ -545,6 +552,7 @@ then
|
||||
|
||||
if [ $EXIT_ON_END == yes ]
|
||||
then
|
||||
echo "[init] Exit from nsh"
|
||||
exit
|
||||
fi
|
||||
|
||||
|
||||
@@ -70,7 +70,6 @@ MODULES += systemcmds/hw_ver
|
||||
MODULES += modules/commander
|
||||
MODULES += modules/navigator
|
||||
MODULES += modules/mavlink
|
||||
MODULES += modules/mavlink_onboard
|
||||
|
||||
#
|
||||
# Estimation modules (EKF/ SO3 / other filters)
|
||||
|
||||
@@ -405,7 +405,7 @@ CONFIG_SIG_SIGWORK=4
|
||||
CONFIG_MAX_TASKS=32
|
||||
CONFIG_MAX_TASK_ARGS=10
|
||||
CONFIG_NPTHREAD_KEYS=4
|
||||
CONFIG_NFILE_DESCRIPTORS=32
|
||||
CONFIG_NFILE_DESCRIPTORS=36
|
||||
CONFIG_NFILE_STREAMS=8
|
||||
CONFIG_NAME_MAX=32
|
||||
CONFIG_PREALLOC_MQ_MSGS=4
|
||||
|
||||
@@ -439,7 +439,7 @@ CONFIG_SIG_SIGWORK=4
|
||||
CONFIG_MAX_TASKS=32
|
||||
CONFIG_MAX_TASK_ARGS=10
|
||||
CONFIG_NPTHREAD_KEYS=4
|
||||
CONFIG_NFILE_DESCRIPTORS=32
|
||||
CONFIG_NFILE_DESCRIPTORS=36
|
||||
CONFIG_NFILE_STREAMS=8
|
||||
CONFIG_NAME_MAX=32
|
||||
CONFIG_PREALLOC_MQ_MSGS=4
|
||||
@@ -796,11 +796,11 @@ CONFIG_SCHED_WORKQUEUE=y
|
||||
CONFIG_SCHED_HPWORK=y
|
||||
CONFIG_SCHED_WORKPRIORITY=192
|
||||
CONFIG_SCHED_WORKPERIOD=5000
|
||||
CONFIG_SCHED_WORKSTACKSIZE=4000
|
||||
CONFIG_SCHED_WORKSTACKSIZE=2000
|
||||
CONFIG_SCHED_LPWORK=y
|
||||
CONFIG_SCHED_LPWORKPRIORITY=50
|
||||
CONFIG_SCHED_LPWORKPERIOD=50000
|
||||
CONFIG_SCHED_LPWORKSTACKSIZE=4000
|
||||
CONFIG_SCHED_LPWORKSTACKSIZE=2000
|
||||
# CONFIG_LIB_KBDCODEC is not set
|
||||
# CONFIG_LIB_SLCDCODEC is not set
|
||||
|
||||
|
||||
@@ -100,6 +100,7 @@ __EXPORT void mavlink_vasprintf(int _fd, int severity, const char *fmt, ...);
|
||||
*/
|
||||
#define mavlink_log_info(_fd, _text, ...) mavlink_vasprintf(_fd, MAVLINK_IOC_SEND_TEXT_INFO, _text, ##__VA_ARGS__);
|
||||
|
||||
|
||||
struct mavlink_logmessage {
|
||||
char text[MAVLINK_LOG_MAXLEN + 1];
|
||||
unsigned char severity;
|
||||
@@ -112,6 +113,7 @@ struct mavlink_logbuffer {
|
||||
struct mavlink_logmessage *elems;
|
||||
};
|
||||
|
||||
__BEGIN_DECLS
|
||||
void mavlink_logbuffer_init(struct mavlink_logbuffer *lb, int size);
|
||||
|
||||
void mavlink_logbuffer_destroy(struct mavlink_logbuffer *lb);
|
||||
@@ -125,6 +127,7 @@ void mavlink_logbuffer_write(struct mavlink_logbuffer *lb, const struct mavlink_
|
||||
int mavlink_logbuffer_read(struct mavlink_logbuffer *lb, struct mavlink_logmessage *elem);
|
||||
|
||||
void mavlink_logbuffer_vasprintf(struct mavlink_logbuffer *lb, int severity, const char *fmt, ...);
|
||||
__END_DECLS
|
||||
|
||||
#endif
|
||||
|
||||
|
||||
+8
-8
@@ -440,14 +440,14 @@ __EXPORT float _wrap_pi(float bearing)
|
||||
}
|
||||
|
||||
int c = 0;
|
||||
while (bearing > M_PI_F) {
|
||||
while (bearing >= M_PI_F) {
|
||||
bearing -= M_TWOPI_F;
|
||||
if (c++ > 3)
|
||||
return NAN;
|
||||
}
|
||||
|
||||
c = 0;
|
||||
while (bearing <= -M_PI_F) {
|
||||
while (bearing < -M_PI_F) {
|
||||
bearing += M_TWOPI_F;
|
||||
if (c++ > 3)
|
||||
return NAN;
|
||||
@@ -464,14 +464,14 @@ __EXPORT float _wrap_2pi(float bearing)
|
||||
}
|
||||
|
||||
int c = 0;
|
||||
while (bearing > M_TWOPI_F) {
|
||||
while (bearing >= M_TWOPI_F) {
|
||||
bearing -= M_TWOPI_F;
|
||||
if (c++ > 3)
|
||||
return NAN;
|
||||
}
|
||||
|
||||
c = 0;
|
||||
while (bearing <= 0.0f) {
|
||||
while (bearing < 0.0f) {
|
||||
bearing += M_TWOPI_F;
|
||||
if (c++ > 3)
|
||||
return NAN;
|
||||
@@ -488,14 +488,14 @@ __EXPORT float _wrap_180(float bearing)
|
||||
}
|
||||
|
||||
int c = 0;
|
||||
while (bearing > 180.0f) {
|
||||
while (bearing >= 180.0f) {
|
||||
bearing -= 360.0f;
|
||||
if (c++ > 3)
|
||||
return NAN;
|
||||
}
|
||||
|
||||
c = 0;
|
||||
while (bearing <= -180.0f) {
|
||||
while (bearing < -180.0f) {
|
||||
bearing += 360.0f;
|
||||
if (c++ > 3)
|
||||
return NAN;
|
||||
@@ -512,14 +512,14 @@ __EXPORT float _wrap_360(float bearing)
|
||||
}
|
||||
|
||||
int c = 0;
|
||||
while (bearing > 360.0f) {
|
||||
while (bearing >= 360.0f) {
|
||||
bearing -= 360.0f;
|
||||
if (c++ > 3)
|
||||
return NAN;
|
||||
}
|
||||
|
||||
c = 0;
|
||||
while (bearing <= 0.0f) {
|
||||
while (bearing < 0.0f) {
|
||||
bearing += 360.0f;
|
||||
if (c++ > 3)
|
||||
return NAN;
|
||||
|
||||
@@ -8,6 +8,8 @@
|
||||
#ifndef PX4_CUSTOM_MODE_H_
|
||||
#define PX4_CUSTOM_MODE_H_
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
enum PX4_CUSTOM_MAIN_MODE {
|
||||
PX4_CUSTOM_MAIN_MODE_MANUAL = 1,
|
||||
PX4_CUSTOM_MAIN_MODE_SEATBELT,
|
||||
|
||||
+25
-760
File diff suppressed because it is too large
Load Diff
@@ -1,7 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
* Author: Lorenz Meier <lm@inf.ethz.ch>
|
||||
* Copyright (c) 2012-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
|
||||
@@ -43,6 +42,8 @@
|
||||
#ifndef MAVLINK_BRIDGE_HEADER_H
|
||||
#define MAVLINK_BRIDGE_HEADER_H
|
||||
|
||||
__BEGIN_DECLS
|
||||
|
||||
#define MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||
|
||||
/* use efficient approach, see mavlink_helpers.h */
|
||||
@@ -73,11 +74,13 @@ extern mavlink_system_t mavlink_system;
|
||||
* @param chan MAVLink channel to use, usually MAVLINK_COMM_0 = UART0
|
||||
* @param ch Character to send
|
||||
*/
|
||||
extern void mavlink_send_uart_bytes(mavlink_channel_t chan, const uint8_t *ch, int length);
|
||||
void mavlink_send_uart_bytes(mavlink_channel_t chan, const uint8_t *ch, int length);
|
||||
|
||||
extern mavlink_status_t *mavlink_get_channel_status(uint8_t chan);
|
||||
extern mavlink_message_t *mavlink_get_channel_buffer(uint8_t chan);
|
||||
|
||||
#include <v1.0/common/mavlink.h>
|
||||
|
||||
__END_DECLS
|
||||
|
||||
#endif /* MAVLINK_BRIDGE_HEADER_H */
|
||||
|
||||
File diff suppressed because it is too large
Load Diff
@@ -0,0 +1,314 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-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_main.h
|
||||
* MAVLink 1.0 protocol interface definition.
|
||||
*
|
||||
* @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
* @author Anton Babushkin <anton.babushkin@me.com>
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <nuttx/fs/fs.h>
|
||||
#include <systemlib/param/param.h>
|
||||
#include <systemlib/perf_counter.h>
|
||||
#include <pthread.h>
|
||||
#include <mavlink/mavlink_log.h>
|
||||
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/mission.h>
|
||||
|
||||
#include "mavlink_bridge_header.h"
|
||||
#include "mavlink_orb_subscription.h"
|
||||
#include "mavlink_stream.h"
|
||||
#include "mavlink_messages.h"
|
||||
|
||||
// FIXME XXX - TO BE MOVED TO XML
|
||||
enum MAVLINK_WPM_STATES {
|
||||
MAVLINK_WPM_STATE_IDLE = 0,
|
||||
MAVLINK_WPM_STATE_SENDLIST,
|
||||
MAVLINK_WPM_STATE_SENDLIST_SENDWPS,
|
||||
MAVLINK_WPM_STATE_GETLIST,
|
||||
MAVLINK_WPM_STATE_GETLIST_GETWPS,
|
||||
MAVLINK_WPM_STATE_GETLIST_GOTALL,
|
||||
MAVLINK_WPM_STATE_ENUM_END
|
||||
};
|
||||
|
||||
enum MAVLINK_WPM_CODES {
|
||||
MAVLINK_WPM_CODE_OK = 0,
|
||||
MAVLINK_WPM_CODE_ERR_WAYPOINT_ACTION_NOT_SUPPORTED,
|
||||
MAVLINK_WPM_CODE_ERR_WAYPOINT_FRAME_NOT_SUPPORTED,
|
||||
MAVLINK_WPM_CODE_ERR_WAYPOINT_OUT_OF_BOUNDS,
|
||||
MAVLINK_WPM_CODE_ERR_WAYPOINT_MAX_NUMBER_EXCEEDED,
|
||||
MAVLINK_WPM_CODE_ENUM_END
|
||||
};
|
||||
|
||||
|
||||
#define MAVLINK_WPM_MAX_WP_COUNT 255
|
||||
#define MAVLINK_WPM_PROTOCOL_TIMEOUT_DEFAULT 5000000 ///< Protocol communication timeout in useconds
|
||||
#define MAVLINK_WPM_SETPOINT_DELAY_DEFAULT 1000000 ///< When to send a new setpoint
|
||||
#define MAVLINK_WPM_PROTOCOL_DELAY_DEFAULT 40000
|
||||
|
||||
|
||||
struct mavlink_wpm_storage {
|
||||
uint16_t size;
|
||||
uint16_t max_size;
|
||||
enum MAVLINK_WPM_STATES current_state;
|
||||
int16_t current_wp_id; ///< Waypoint in current transmission
|
||||
uint16_t current_count;
|
||||
uint8_t current_partner_sysid;
|
||||
uint8_t current_partner_compid;
|
||||
uint64_t timestamp_lastaction;
|
||||
uint64_t timestamp_last_send_setpoint;
|
||||
uint32_t timeout;
|
||||
int current_dataman_id;
|
||||
};
|
||||
|
||||
|
||||
class Mavlink
|
||||
{
|
||||
|
||||
public:
|
||||
/**
|
||||
* Constructor
|
||||
*/
|
||||
Mavlink();
|
||||
|
||||
/**
|
||||
* Destructor, also kills the mavlinks task.
|
||||
*/
|
||||
~Mavlink();
|
||||
|
||||
/**
|
||||
* Start the mavlink task.
|
||||
*
|
||||
* @return OK on success.
|
||||
*/
|
||||
static int start(int argc, char *argv[]);
|
||||
|
||||
/**
|
||||
* Display the mavlink status.
|
||||
*/
|
||||
void status();
|
||||
|
||||
static int stream(int argc, char *argv[]);
|
||||
|
||||
static int instance_count();
|
||||
|
||||
static Mavlink *new_instance();
|
||||
|
||||
static Mavlink *get_instance(unsigned instance);
|
||||
|
||||
static Mavlink *get_instance_for_device(const char *device_name);
|
||||
|
||||
static int destroy_all_instances();
|
||||
|
||||
static bool instance_exists(const char *device_name, Mavlink *self);
|
||||
|
||||
static int get_uart_fd(unsigned index);
|
||||
|
||||
int get_uart_fd();
|
||||
|
||||
const char *_device_name;
|
||||
|
||||
enum MAVLINK_MODE {
|
||||
MODE_CUSTOM = 0,
|
||||
MODE_OFFBOARD,
|
||||
MODE_ONBOARD,
|
||||
MODE_HIL
|
||||
};
|
||||
|
||||
void set_mode(enum MAVLINK_MODE);
|
||||
enum MAVLINK_MODE get_mode() { return _mode; }
|
||||
|
||||
bool get_hil_enabled() { return _mavlink_hil_enabled; };
|
||||
|
||||
/**
|
||||
* Handle waypoint related messages.
|
||||
*/
|
||||
void mavlink_wpm_message_handler(const mavlink_message_t *msg);
|
||||
|
||||
static int start_helper(int argc, char *argv[]);
|
||||
|
||||
/**
|
||||
* Handle parameter related messages.
|
||||
*/
|
||||
void mavlink_pm_message_handler(const mavlink_channel_t chan, const mavlink_message_t *msg);
|
||||
|
||||
void get_mavlink_mode_and_state(struct vehicle_status_s *status, struct position_setpoint_triplet_s *pos_sp_triplet, uint8_t *mavlink_state, uint8_t *mavlink_base_mode, uint32_t *mavlink_custom_mode);
|
||||
|
||||
/**
|
||||
* Enable / disable Hardware in the Loop simulation mode.
|
||||
*
|
||||
* @param hil_enabled The new HIL enable/disable state.
|
||||
* @return OK if the HIL state changed, ERROR if the
|
||||
* requested change could not be made or was
|
||||
* redundant.
|
||||
*/
|
||||
int set_hil_enabled(bool hil_enabled);
|
||||
|
||||
MavlinkOrbSubscription *add_orb_subscription(const orb_id_t topic);
|
||||
|
||||
int get_instance_id();
|
||||
|
||||
mavlink_channel_t get_channel();
|
||||
|
||||
bool _task_should_exit; /**< if true, mavlink task should exit */
|
||||
|
||||
protected:
|
||||
Mavlink *next;
|
||||
|
||||
private:
|
||||
int _instance_id;
|
||||
|
||||
int _mavlink_fd;
|
||||
bool _task_running;
|
||||
|
||||
perf_counter_t _loop_perf; /**< loop performance counter */
|
||||
|
||||
/* states */
|
||||
bool _mavlink_hil_enabled; /**< Hardware In the Loop mode */
|
||||
|
||||
unsigned _main_loop_delay; /**< mainloop delay, depends on data rate */
|
||||
|
||||
MavlinkOrbSubscription *_subscriptions;
|
||||
MavlinkStream *_streams;
|
||||
|
||||
orb_advert_t _mission_pub;
|
||||
struct mission_s mission;
|
||||
uint8_t missionlib_msg_buf[MAVLINK_MAX_PACKET_LEN];
|
||||
MAVLINK_MODE _mode;
|
||||
|
||||
uint8_t _mavlink_wpm_comp_id;
|
||||
mavlink_channel_t _channel;
|
||||
|
||||
struct mavlink_logbuffer _logbuffer;
|
||||
unsigned int _total_counter;
|
||||
|
||||
pthread_t _receive_thread;
|
||||
|
||||
/* Allocate storage space for waypoints */
|
||||
mavlink_wpm_storage _wpm_s;
|
||||
mavlink_wpm_storage *_wpm;
|
||||
|
||||
bool _verbose;
|
||||
int _uart_fd;
|
||||
int _baudrate;
|
||||
int _datarate;
|
||||
|
||||
/**
|
||||
* If the queue index is not at 0, the queue sending
|
||||
* logic will send parameters from the current index
|
||||
* to len - 1, the end of the param list.
|
||||
*/
|
||||
unsigned int _mavlink_param_queue_index;
|
||||
|
||||
bool mavlink_link_termination_allowed;
|
||||
|
||||
char *_subscribe_to_stream;
|
||||
float _subscribe_to_stream_rate;
|
||||
|
||||
/**
|
||||
* Send one parameter.
|
||||
*
|
||||
* @param param The parameter id to send.
|
||||
* @return zero on success, nonzero on failure.
|
||||
*/
|
||||
int mavlink_pm_send_param(param_t param);
|
||||
|
||||
/**
|
||||
* Send one parameter identified by index.
|
||||
*
|
||||
* @param index The index of the parameter to send.
|
||||
* @return zero on success, nonzero else.
|
||||
*/
|
||||
int mavlink_pm_send_param_for_index(uint16_t index);
|
||||
|
||||
/**
|
||||
* Send one parameter identified by name.
|
||||
*
|
||||
* @param name The index of the parameter to send.
|
||||
* @return zero on success, nonzero else.
|
||||
*/
|
||||
int mavlink_pm_send_param_for_name(const char *name);
|
||||
|
||||
/**
|
||||
* Send a queue of parameters, one parameter per function call.
|
||||
*
|
||||
* @return zero on success, nonzero on failure
|
||||
*/
|
||||
int mavlink_pm_queued_send(void);
|
||||
|
||||
/**
|
||||
* Start sending the parameter queue.
|
||||
*
|
||||
* This function will not directly send parameters, but instead
|
||||
* activate the sending of one parameter on each call of
|
||||
* mavlink_pm_queued_send().
|
||||
* @see mavlink_pm_queued_send()
|
||||
*/
|
||||
void mavlink_pm_start_queued_send();
|
||||
|
||||
void mavlink_update_system();
|
||||
|
||||
void mavlink_waypoint_eventloop(uint64_t now);
|
||||
void mavlink_wpm_send_waypoint_reached(uint16_t seq);
|
||||
void mavlink_wpm_send_waypoint_request(uint8_t sysid, uint8_t compid, uint16_t seq);
|
||||
void mavlink_wpm_send_waypoint(uint8_t sysid, uint8_t compid, uint16_t seq);
|
||||
void mavlink_wpm_send_waypoint_count(uint8_t sysid, uint8_t compid, uint16_t count);
|
||||
void mavlink_wpm_send_waypoint_current(uint16_t seq);
|
||||
void mavlink_wpm_send_waypoint_ack(uint8_t sysid, uint8_t compid, uint8_t type);
|
||||
void mavlink_wpm_init(mavlink_wpm_storage *state);
|
||||
int map_mission_item_to_mavlink_mission_item(const struct mission_item_s *mission_item, mavlink_mission_item_t *mavlink_mission_item);
|
||||
int map_mavlink_mission_item_to_mission_item(const mavlink_mission_item_t *mavlink_mission_item, struct mission_item_s *mission_item);
|
||||
void publish_mission();
|
||||
|
||||
void mavlink_missionlib_send_message(mavlink_message_t *msg);
|
||||
int mavlink_missionlib_send_gcs_string(const char *string);
|
||||
|
||||
int mavlink_open_uart(int baudrate, const char *uart_name, struct termios *uart_config_original, bool *is_usb);
|
||||
|
||||
int configure_stream(const char *stream_name, const float rate);
|
||||
void configure_stream_threadsafe(const char *stream_name, const float rate);
|
||||
|
||||
static int mavlink_dev_ioctl(struct file *filep, int cmd, unsigned long arg);
|
||||
|
||||
/**
|
||||
* Main mavlink task.
|
||||
*/
|
||||
int task_main(int argc, char *argv[]);
|
||||
|
||||
};
|
||||
File diff suppressed because it is too large
Load Diff
@@ -1,7 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
* Author: @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
* Copyright (c) 2012-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
|
||||
@@ -33,20 +32,17 @@
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file mavlink_hil.h
|
||||
* Hardware-in-the-loop simulation support.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
extern bool mavlink_hil_enabled;
|
||||
|
||||
/**
|
||||
* Enable / disable Hardware in the Loop simulation mode.
|
||||
* @file mavlink_messages.h
|
||||
* MAVLink 1.0 message formatters definition.
|
||||
*
|
||||
* @param hil_enabled The new HIL enable/disable state.
|
||||
* @return OK if the HIL state changed, ERROR if the
|
||||
* requested change could not be made or was
|
||||
* redundant.
|
||||
* @author Anton Babushkin <anton.babushkin@me.com>
|
||||
*/
|
||||
extern int set_hil_on_off(bool hil_enabled);
|
||||
|
||||
#ifndef MAVLINK_MESSAGES_H_
|
||||
#define MAVLINK_MESSAGES_H_
|
||||
|
||||
#include "mavlink_stream.h"
|
||||
|
||||
extern MavlinkStream *streams_list[];
|
||||
|
||||
#endif /* MAVLINK_MESSAGES_H_ */
|
||||
+44
-38
@@ -1,7 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
* Author: Lorenz Meier <lm@inf.ethz.ch>
|
||||
* 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
|
||||
@@ -33,51 +32,58 @@
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file mavlink_bridge_header
|
||||
* MAVLink bridge header for UART access.
|
||||
* @file mavlink_orb_subscription.cpp
|
||||
* uORB subscription implementation.
|
||||
*
|
||||
* @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
* @author Anton Babushkin <anton.babushkin@me.com>
|
||||
*/
|
||||
|
||||
/* MAVLink adapter header */
|
||||
#ifndef MAVLINK_BRIDGE_HEADER_H
|
||||
#define MAVLINK_BRIDGE_HEADER_H
|
||||
|
||||
#define MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||
|
||||
/* use efficient approach, see mavlink_helpers.h */
|
||||
#define MAVLINK_SEND_UART_BYTES mavlink_send_uart_bytes
|
||||
|
||||
#define MAVLINK_GET_CHANNEL_BUFFER mavlink_get_channel_buffer
|
||||
#define MAVLINK_GET_CHANNEL_STATUS mavlink_get_channel_status
|
||||
|
||||
#include <v1.0/mavlink_types.h>
|
||||
#include <unistd.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include <uORB/uORB.h>
|
||||
#include <stdio.h>
|
||||
|
||||
#include "mavlink_orb_subscription.h"
|
||||
|
||||
/* Struct that stores the communication settings of this system.
|
||||
you can also define / alter these settings elsewhere, as long
|
||||
as they're included BEFORE mavlink.h.
|
||||
So you can set the
|
||||
MavlinkOrbSubscription::MavlinkOrbSubscription(const orb_id_t topic) : _topic(topic), _last_check(0), next(nullptr)
|
||||
{
|
||||
_data = malloc(topic->o_size);
|
||||
memset(_data, 0, topic->o_size);
|
||||
_fd = orb_subscribe(_topic);
|
||||
}
|
||||
|
||||
mavlink_system.sysid = 100; // System ID, 1-255
|
||||
mavlink_system.compid = 50; // Component/Subsystem ID, 1-255
|
||||
MavlinkOrbSubscription::~MavlinkOrbSubscription()
|
||||
{
|
||||
close(_fd);
|
||||
free(_data);
|
||||
}
|
||||
|
||||
Lines also in your main.c, e.g. by reading these parameter from EEPROM.
|
||||
*/
|
||||
extern mavlink_system_t mavlink_system;
|
||||
const orb_id_t
|
||||
MavlinkOrbSubscription::get_topic()
|
||||
{
|
||||
return _topic;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send multiple chars (uint8_t) over a comm channel
|
||||
*
|
||||
* @param chan MAVLink channel to use, usually MAVLINK_COMM_0 = UART0
|
||||
* @param ch Character to send
|
||||
*/
|
||||
extern void mavlink_send_uart_bytes(mavlink_channel_t chan, uint8_t *ch, int length);
|
||||
void *
|
||||
MavlinkOrbSubscription::get_data()
|
||||
{
|
||||
return _data;
|
||||
}
|
||||
|
||||
mavlink_status_t* mavlink_get_channel_status(uint8_t chan);
|
||||
mavlink_message_t* mavlink_get_channel_buffer(uint8_t chan);
|
||||
bool
|
||||
MavlinkOrbSubscription::update(const hrt_abstime t)
|
||||
{
|
||||
if (_last_check != t) {
|
||||
_last_check = t;
|
||||
bool updated;
|
||||
orb_check(_fd, &updated);
|
||||
|
||||
#include <v1.0/common/mavlink.h>
|
||||
if (updated) {
|
||||
orb_copy(_topic, _fd, _data);
|
||||
return true;
|
||||
}
|
||||
}
|
||||
|
||||
#endif /* MAVLINK_BRIDGE_HEADER_H */
|
||||
return false;
|
||||
}
|
||||
@@ -0,0 +1,68 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* 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_orb_subscription.h
|
||||
* uORB subscription definition.
|
||||
*
|
||||
* @author Anton Babushkin <anton.babushkin@me.com>
|
||||
*/
|
||||
|
||||
#ifndef MAVLINK_ORB_SUBSCRIPTION_H_
|
||||
#define MAVLINK_ORB_SUBSCRIPTION_H_
|
||||
|
||||
#include <systemlib/uthash/utlist.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
|
||||
|
||||
class MavlinkOrbSubscription
|
||||
{
|
||||
public:
|
||||
MavlinkOrbSubscription *next;
|
||||
|
||||
MavlinkOrbSubscription(const orb_id_t topic);
|
||||
~MavlinkOrbSubscription();
|
||||
|
||||
bool update(const hrt_abstime t);
|
||||
void *get_data();
|
||||
const orb_id_t get_topic();
|
||||
|
||||
private:
|
||||
const orb_id_t _topic;
|
||||
int _fd;
|
||||
void *_data;
|
||||
hrt_abstime _last_check;
|
||||
};
|
||||
|
||||
|
||||
#endif /* MAVLINK_ORB_SUBSCRIPTION_H_ */
|
||||
@@ -1,230 +0,0 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
* Author: Lorenz Meier <lm@inf.ethz.ch>
|
||||
*
|
||||
* 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_parameters.c
|
||||
* MAVLink parameter protocol implementation (BSD-relicensed).
|
||||
*
|
||||
* @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
*/
|
||||
|
||||
#include "mavlink_bridge_header.h"
|
||||
#include "mavlink_parameters.h"
|
||||
#include <uORB/uORB.h>
|
||||
#include "math.h" /* isinf / isnan checks */
|
||||
#include <assert.h>
|
||||
#include <stdio.h>
|
||||
#include <fcntl.h>
|
||||
#include <unistd.h>
|
||||
#include <stdbool.h>
|
||||
#include <string.h>
|
||||
#include <errno.h>
|
||||
#include <systemlib/param/param.h>
|
||||
#include <systemlib/err.h>
|
||||
#include <sys/stat.h>
|
||||
|
||||
extern mavlink_system_t mavlink_system;
|
||||
|
||||
extern int mavlink_missionlib_send_message(mavlink_message_t *msg);
|
||||
extern int mavlink_missionlib_send_gcs_string(const char *string);
|
||||
|
||||
/**
|
||||
* If the queue index is not at 0, the queue sending
|
||||
* logic will send parameters from the current index
|
||||
* to len - 1, the end of the param list.
|
||||
*/
|
||||
static unsigned int mavlink_param_queue_index = 0;
|
||||
|
||||
/**
|
||||
* Callback for param interface.
|
||||
*/
|
||||
void mavlink_pm_callback(void *arg, param_t param);
|
||||
|
||||
void mavlink_pm_callback(void *arg, param_t param)
|
||||
{
|
||||
mavlink_pm_send_param(param);
|
||||
usleep(*(unsigned int *)arg);
|
||||
}
|
||||
|
||||
void mavlink_pm_send_all_params(unsigned int delay)
|
||||
{
|
||||
unsigned int dbuf = delay;
|
||||
param_foreach(&mavlink_pm_callback, &dbuf, false);
|
||||
}
|
||||
|
||||
int mavlink_pm_queued_send()
|
||||
{
|
||||
if (mavlink_param_queue_index < param_count()) {
|
||||
mavlink_pm_send_param(param_for_index(mavlink_param_queue_index));
|
||||
mavlink_param_queue_index++;
|
||||
return 0;
|
||||
|
||||
} else {
|
||||
return 1;
|
||||
}
|
||||
}
|
||||
|
||||
void mavlink_pm_start_queued_send()
|
||||
{
|
||||
mavlink_param_queue_index = 0;
|
||||
}
|
||||
|
||||
int mavlink_pm_send_param_for_index(uint16_t index)
|
||||
{
|
||||
return mavlink_pm_send_param(param_for_index(index));
|
||||
}
|
||||
|
||||
int mavlink_pm_send_param_for_name(const char *name)
|
||||
{
|
||||
return mavlink_pm_send_param(param_find(name));
|
||||
}
|
||||
|
||||
int mavlink_pm_send_param(param_t param)
|
||||
{
|
||||
if (param == PARAM_INVALID) return 1;
|
||||
|
||||
/* buffers for param transmission */
|
||||
static char name_buf[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN];
|
||||
float val_buf;
|
||||
static mavlink_message_t tx_msg;
|
||||
|
||||
/* query parameter type */
|
||||
param_type_t type = param_type(param);
|
||||
/* copy parameter name */
|
||||
strncpy((char *)name_buf, param_name(param), MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
|
||||
|
||||
/*
|
||||
* Map onboard parameter type to MAVLink type,
|
||||
* endianess matches (both little endian)
|
||||
*/
|
||||
uint8_t mavlink_type;
|
||||
|
||||
if (type == PARAM_TYPE_INT32) {
|
||||
mavlink_type = MAVLINK_TYPE_INT32_T;
|
||||
|
||||
} else if (type == PARAM_TYPE_FLOAT) {
|
||||
mavlink_type = MAVLINK_TYPE_FLOAT;
|
||||
|
||||
} else {
|
||||
mavlink_type = MAVLINK_TYPE_FLOAT;
|
||||
}
|
||||
|
||||
/*
|
||||
* get param value, since MAVLink encodes float and int params in the same
|
||||
* space during transmission, copy param onto float val_buf
|
||||
*/
|
||||
|
||||
int ret;
|
||||
|
||||
if ((ret = param_get(param, &val_buf)) != OK) {
|
||||
return ret;
|
||||
}
|
||||
|
||||
mavlink_msg_param_value_pack_chan(mavlink_system.sysid,
|
||||
mavlink_system.compid,
|
||||
MAVLINK_COMM_0,
|
||||
&tx_msg,
|
||||
name_buf,
|
||||
val_buf,
|
||||
mavlink_type,
|
||||
param_count(),
|
||||
param_get_index(param));
|
||||
ret = mavlink_missionlib_send_message(&tx_msg);
|
||||
return ret;
|
||||
}
|
||||
|
||||
void mavlink_pm_message_handler(const mavlink_channel_t chan, const mavlink_message_t *msg)
|
||||
{
|
||||
switch (msg->msgid) {
|
||||
case MAVLINK_MSG_ID_PARAM_REQUEST_LIST: {
|
||||
/* Start sending parameters */
|
||||
mavlink_pm_start_queued_send();
|
||||
mavlink_missionlib_send_gcs_string("[mavlink pm] sending list");
|
||||
} break;
|
||||
|
||||
case MAVLINK_MSG_ID_PARAM_SET: {
|
||||
|
||||
/* Handle parameter setting */
|
||||
|
||||
if (msg->msgid == MAVLINK_MSG_ID_PARAM_SET) {
|
||||
mavlink_param_set_t mavlink_param_set;
|
||||
mavlink_msg_param_set_decode(msg, &mavlink_param_set);
|
||||
|
||||
if (mavlink_param_set.target_system == mavlink_system.sysid && ((mavlink_param_set.target_component == mavlink_system.compid) || (mavlink_param_set.target_component == MAV_COMP_ID_ALL))) {
|
||||
/* local name buffer to enforce null-terminated string */
|
||||
char name[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN + 1];
|
||||
strncpy(name, mavlink_param_set.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
|
||||
/* enforce null termination */
|
||||
name[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN] = '\0';
|
||||
/* attempt to find parameter, set and send it */
|
||||
param_t param = param_find(name);
|
||||
|
||||
if (param == PARAM_INVALID) {
|
||||
char buf[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN];
|
||||
sprintf(buf, "[mavlink pm] unknown: %s", name);
|
||||
mavlink_missionlib_send_gcs_string(buf);
|
||||
|
||||
} else {
|
||||
/* set and send parameter */
|
||||
param_set(param, &(mavlink_param_set.param_value));
|
||||
mavlink_pm_send_param(param);
|
||||
}
|
||||
}
|
||||
}
|
||||
} break;
|
||||
|
||||
case MAVLINK_MSG_ID_PARAM_REQUEST_READ: {
|
||||
mavlink_param_request_read_t mavlink_param_request_read;
|
||||
mavlink_msg_param_request_read_decode(msg, &mavlink_param_request_read);
|
||||
|
||||
if (mavlink_param_request_read.target_system == mavlink_system.sysid && ((mavlink_param_request_read.target_component == mavlink_system.compid) || (mavlink_param_request_read.target_component == MAV_COMP_ID_ALL))) {
|
||||
/* when no index is given, loop through string ids and compare them */
|
||||
if (mavlink_param_request_read.param_index == -1) {
|
||||
/* local name buffer to enforce null-terminated string */
|
||||
char name[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN + 1];
|
||||
strncpy(name, mavlink_param_request_read.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
|
||||
/* enforce null termination */
|
||||
name[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN] = '\0';
|
||||
/* attempt to find parameter and send it */
|
||||
mavlink_pm_send_param_for_name(name);
|
||||
|
||||
} else {
|
||||
/* when index is >= 0, send this parameter again */
|
||||
mavlink_pm_send_param_for_index(mavlink_param_request_read.param_index);
|
||||
}
|
||||
}
|
||||
|
||||
} break;
|
||||
}
|
||||
}
|
||||
@@ -1,104 +0,0 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
* Author: Lorenz Meier <lm@inf.ethz.ch>
|
||||
*
|
||||
* 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_parameters.h
|
||||
* MAVLink parameter protocol definitions (BSD-relicensed).
|
||||
*
|
||||
* @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
*/
|
||||
|
||||
/* This assumes you have the mavlink headers on your include path
|
||||
or in the same folder as this source file */
|
||||
|
||||
|
||||
#include <v1.0/mavlink_types.h>
|
||||
#include <stdbool.h>
|
||||
#include <systemlib/param/param.h>
|
||||
|
||||
/**
|
||||
* Handle parameter related messages.
|
||||
*/
|
||||
void mavlink_pm_message_handler(const mavlink_channel_t chan, const mavlink_message_t *msg);
|
||||
|
||||
/**
|
||||
* Send all parameters at once.
|
||||
*
|
||||
* This function blocks until all parameters have been sent.
|
||||
* it delays each parameter by the passed amount of microseconds.
|
||||
*
|
||||
* @param delay The delay in us between sending all parameters.
|
||||
*/
|
||||
void mavlink_pm_send_all_params(unsigned int delay);
|
||||
|
||||
/**
|
||||
* Send one parameter.
|
||||
*
|
||||
* @param param The parameter id to send.
|
||||
* @return zero on success, nonzero on failure.
|
||||
*/
|
||||
int mavlink_pm_send_param(param_t param);
|
||||
|
||||
/**
|
||||
* Send one parameter identified by index.
|
||||
*
|
||||
* @param index The index of the parameter to send.
|
||||
* @return zero on success, nonzero else.
|
||||
*/
|
||||
int mavlink_pm_send_param_for_index(uint16_t index);
|
||||
|
||||
/**
|
||||
* Send one parameter identified by name.
|
||||
*
|
||||
* @param name The index of the parameter to send.
|
||||
* @return zero on success, nonzero else.
|
||||
*/
|
||||
int mavlink_pm_send_param_for_name(const char *name);
|
||||
|
||||
/**
|
||||
* Send a queue of parameters, one parameter per function call.
|
||||
*
|
||||
* @return zero on success, nonzero on failure
|
||||
*/
|
||||
int mavlink_pm_queued_send(void);
|
||||
|
||||
/**
|
||||
* Start sending the parameter queue.
|
||||
*
|
||||
* This function will not directly send parameters, but instead
|
||||
* activate the sending of one parameter on each call of
|
||||
* mavlink_pm_queued_send().
|
||||
* @see mavlink_pm_queued_send()
|
||||
*/
|
||||
void mavlink_pm_start_queued_send(void);
|
||||
@@ -0,0 +1,72 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* 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_rate_limiter.cpp
|
||||
* Message rate limiter implementation.
|
||||
*
|
||||
* @author Anton Babushkin <anton.babushkin@me.com>
|
||||
*/
|
||||
|
||||
#include "mavlink_rate_limiter.h"
|
||||
|
||||
MavlinkRateLimiter::MavlinkRateLimiter() : _last_sent(0), _interval(1000000)
|
||||
{
|
||||
}
|
||||
|
||||
MavlinkRateLimiter::MavlinkRateLimiter(unsigned int interval) : _last_sent(0), _interval(interval)
|
||||
{
|
||||
}
|
||||
|
||||
MavlinkRateLimiter::~MavlinkRateLimiter()
|
||||
{
|
||||
}
|
||||
|
||||
void
|
||||
MavlinkRateLimiter::set_interval(unsigned int interval)
|
||||
{
|
||||
_interval = interval;
|
||||
}
|
||||
|
||||
bool
|
||||
MavlinkRateLimiter::check(hrt_abstime t)
|
||||
{
|
||||
uint64_t dt = t - _last_sent;
|
||||
|
||||
if (dt > 0 && dt >= _interval) {
|
||||
_last_sent = (t / _interval) * _interval;
|
||||
return true;
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
@@ -1,7 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
* Author: @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
* 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
|
||||
@@ -33,23 +32,31 @@
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file util.h
|
||||
* Utility and helper functions and data.
|
||||
* @file mavlink_rate_limiter.h
|
||||
* Message rate limiter definition.
|
||||
*
|
||||
* @author Anton Babushkin <anton.babushkin@me.com>
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
#ifndef MAVLINK_RATE_LIMITER_H_
|
||||
#define MAVLINK_RATE_LIMITER_H_
|
||||
|
||||
#include "orb_topics.h"
|
||||
#include <drivers/drv_hrt.h>
|
||||
|
||||
/** MAVLink communications channel */
|
||||
extern uint8_t chan;
|
||||
|
||||
/** Shutdown marker */
|
||||
extern volatile bool thread_should_exit;
|
||||
class MavlinkRateLimiter
|
||||
{
|
||||
private:
|
||||
hrt_abstime _last_sent;
|
||||
hrt_abstime _interval;
|
||||
|
||||
/**
|
||||
* Translate the custom state into standard mavlink modes and state.
|
||||
*/
|
||||
extern void
|
||||
get_mavlink_mode_and_state(const struct vehicle_control_mode_s *control_mode, const struct actuator_armed_s *armed,
|
||||
uint8_t *mavlink_state, uint8_t *mavlink_mode);
|
||||
public:
|
||||
MavlinkRateLimiter();
|
||||
MavlinkRateLimiter(unsigned int interval);
|
||||
~MavlinkRateLimiter();
|
||||
void set_interval(unsigned int interval);
|
||||
bool check(hrt_abstime t);
|
||||
};
|
||||
|
||||
|
||||
#endif /* MAVLINK_RATE_LIMITER_H_ */
|
||||
File diff suppressed because it is too large
Load Diff
@@ -1,7 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2008-2012 PX4 Development Team. All rights reserved.
|
||||
* Author: @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
* Copyright (c) 2012-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
|
||||
@@ -33,12 +32,15 @@
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file orb_topics.h
|
||||
* Common sets of topics subscribed to or published by the MAVLink driver,
|
||||
* and structures maintained by those subscriptions.
|
||||
* @file mavlink_orb_listener.h
|
||||
* MAVLink 1.0 uORB listener definition
|
||||
*
|
||||
* @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <systemlib/perf_counter.h>
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/sensor_combined.h>
|
||||
#include <uORB/topics/rc_channels.h>
|
||||
@@ -55,7 +57,6 @@
|
||||
#include <uORB/topics/vehicle_vicon_position.h>
|
||||
#include <uORB/topics/vehicle_attitude_setpoint.h>
|
||||
#include <uORB/topics/vehicle_rates_setpoint.h>
|
||||
#include <uORB/topics/vehicle_control_mode.h>
|
||||
#include <uORB/topics/optical_flow.h>
|
||||
#include <uORB/topics/actuator_outputs.h>
|
||||
#include <uORB/topics/actuator_controls_effective.h>
|
||||
@@ -66,59 +67,81 @@
|
||||
#include <uORB/topics/debug_key_value.h>
|
||||
#include <uORB/topics/airspeed.h>
|
||||
#include <uORB/topics/battery_status.h>
|
||||
#include <drivers/drv_rc_input.h>
|
||||
#include <uORB/topics/navigation_capabilities.h>
|
||||
|
||||
struct mavlink_subscriptions {
|
||||
int sensor_sub;
|
||||
int att_sub;
|
||||
int global_pos_sub;
|
||||
int act_0_sub;
|
||||
int act_1_sub;
|
||||
int act_2_sub;
|
||||
int act_3_sub;
|
||||
int gps_sub;
|
||||
int man_control_sp_sub;
|
||||
int safety_sub;
|
||||
int actuators_sub;
|
||||
int armed_sub;
|
||||
int actuators_effective_sub;
|
||||
int local_pos_sub;
|
||||
int spa_sub;
|
||||
int spl_sub;
|
||||
int triplet_sub;
|
||||
int debug_key_value;
|
||||
int input_rc_sub;
|
||||
int optical_flow;
|
||||
int rates_setpoint_sub;
|
||||
int home_sub;
|
||||
int airspeed_sub;
|
||||
int navigation_capabilities_sub;
|
||||
int position_setpoint_triplet_sub;
|
||||
class Mavlink;
|
||||
|
||||
class MavlinkReceiver
|
||||
{
|
||||
public:
|
||||
/**
|
||||
* Constructor
|
||||
*/
|
||||
MavlinkReceiver(Mavlink *parent);
|
||||
|
||||
/**
|
||||
* Destructor, also kills the mavlinks task.
|
||||
*/
|
||||
~MavlinkReceiver();
|
||||
|
||||
/**
|
||||
* Start the mavlink task.
|
||||
*
|
||||
* @return OK on success.
|
||||
*/
|
||||
int start();
|
||||
|
||||
/**
|
||||
* Display the mavlink status.
|
||||
*/
|
||||
void print_status();
|
||||
|
||||
static pthread_t receive_start(Mavlink *parent);
|
||||
|
||||
static void *start_helper(void *context);
|
||||
|
||||
private:
|
||||
perf_counter_t _loop_perf; /**< loop performance counter */
|
||||
|
||||
Mavlink *_mavlink;
|
||||
|
||||
void handle_message(mavlink_message_t *msg);
|
||||
void handle_message_command_long(mavlink_message_t *msg);
|
||||
void handle_message_optical_flow(mavlink_message_t *msg);
|
||||
void handle_message_set_mode(mavlink_message_t *msg);
|
||||
void handle_message_vicon_position_estimate(mavlink_message_t *msg);
|
||||
void handle_message_quad_swarm_roll_pitch_yaw_thrust(mavlink_message_t *msg);
|
||||
void handle_message_radio_status(mavlink_message_t *msg);
|
||||
void handle_message_manual_control(mavlink_message_t *msg);
|
||||
void handle_message_hil_sensor(mavlink_message_t *msg);
|
||||
void handle_message_hil_gps(mavlink_message_t *msg);
|
||||
void handle_message_hil_state_quaternion(mavlink_message_t *msg);
|
||||
|
||||
void *receive_thread(void *arg);
|
||||
|
||||
mavlink_status_t status;
|
||||
struct vehicle_local_position_s hil_local_pos;
|
||||
int _manual_sub;
|
||||
orb_advert_t _global_pos_pub;
|
||||
orb_advert_t _local_pos_pub;
|
||||
orb_advert_t _attitude_pub;
|
||||
orb_advert_t _gps_pub;
|
||||
orb_advert_t _sensors_pub;
|
||||
orb_advert_t _gyro_pub;
|
||||
orb_advert_t _accel_pub;
|
||||
orb_advert_t _mag_pub;
|
||||
orb_advert_t _baro_pub;
|
||||
orb_advert_t _airspeed_pub;
|
||||
orb_advert_t _battery_pub;
|
||||
orb_advert_t _cmd_pub;
|
||||
orb_advert_t _flow_pub;
|
||||
orb_advert_t _offboard_control_sp_pub;
|
||||
orb_advert_t _vicon_position_pub;
|
||||
orb_advert_t _telemetry_status_pub;
|
||||
orb_advert_t _rc_pub;
|
||||
orb_advert_t _manual_pub;
|
||||
int _hil_counter;
|
||||
int _hil_frames;
|
||||
uint64_t _old_timestamp;
|
||||
bool _hil_local_proj_inited;
|
||||
float _hil_local_alt0;
|
||||
};
|
||||
|
||||
extern struct mavlink_subscriptions mavlink_subs;
|
||||
|
||||
/** Global position */
|
||||
extern struct vehicle_global_position_s global_pos;
|
||||
|
||||
/** Local position */
|
||||
extern struct vehicle_local_position_s local_pos;
|
||||
|
||||
/** navigation capabilities */
|
||||
extern struct navigation_capabilities_s nav_cap;
|
||||
|
||||
/** Vehicle status */
|
||||
extern struct vehicle_status_s v_status;
|
||||
|
||||
/** Position setpoint triplet */
|
||||
extern struct position_setpoint_triplet_s pos_sp_triplet;
|
||||
|
||||
/** RC channels */
|
||||
extern struct rc_channels_s rc;
|
||||
|
||||
/** Actuator armed state */
|
||||
extern struct actuator_armed_s armed;
|
||||
|
||||
/** Worker thread starter */
|
||||
extern pthread_t uorb_receive_start(void);
|
||||
@@ -0,0 +1,85 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* 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_stream.cpp
|
||||
* Mavlink messages stream implementation.
|
||||
*
|
||||
* @author Anton Babushkin <anton.babushkin@me.com>
|
||||
*/
|
||||
|
||||
#include <stdlib.h>
|
||||
|
||||
#include "mavlink_stream.h"
|
||||
#include "mavlink_main.h"
|
||||
|
||||
MavlinkStream::MavlinkStream() : _interval(1000000), _last_sent(0), _channel(MAVLINK_COMM_0), next(nullptr)
|
||||
{
|
||||
}
|
||||
|
||||
MavlinkStream::~MavlinkStream()
|
||||
{
|
||||
}
|
||||
|
||||
/**
|
||||
* Set messages interval in ms
|
||||
*/
|
||||
void
|
||||
MavlinkStream::set_interval(const unsigned int interval)
|
||||
{
|
||||
_interval = interval;
|
||||
}
|
||||
|
||||
/**
|
||||
* Set mavlink channel
|
||||
*/
|
||||
void
|
||||
MavlinkStream::set_channel(mavlink_channel_t channel)
|
||||
{
|
||||
_channel = channel;
|
||||
}
|
||||
|
||||
/**
|
||||
* Update subscriptions and send message if necessary
|
||||
*/
|
||||
int
|
||||
MavlinkStream::update(const hrt_abstime t)
|
||||
{
|
||||
uint64_t dt = t - _last_sent;
|
||||
|
||||
if (dt > 0 && dt >= _interval) {
|
||||
/* interval expired, send message */
|
||||
send(t);
|
||||
_last_sent = (t / _interval) * _interval;
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,76 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* 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_stream.cpp
|
||||
* Mavlink messages stream definition.
|
||||
*
|
||||
* @author Anton Babushkin <anton.babushkin@me.com>
|
||||
*/
|
||||
|
||||
#ifndef MAVLINK_STREAM_H_
|
||||
#define MAVLINK_STREAM_H_
|
||||
|
||||
#include <drivers/drv_hrt.h>
|
||||
|
||||
class Mavlink;
|
||||
class MavlinkStream;
|
||||
|
||||
#include "mavlink_main.h"
|
||||
|
||||
class MavlinkStream
|
||||
{
|
||||
private:
|
||||
hrt_abstime _last_sent;
|
||||
|
||||
protected:
|
||||
mavlink_channel_t _channel;
|
||||
unsigned int _interval;
|
||||
|
||||
virtual void send(const hrt_abstime t) = 0;
|
||||
|
||||
public:
|
||||
MavlinkStream *next;
|
||||
|
||||
MavlinkStream();
|
||||
~MavlinkStream();
|
||||
void set_interval(const unsigned int interval);
|
||||
void set_channel(mavlink_channel_t channel);
|
||||
int update(const hrt_abstime t);
|
||||
virtual MavlinkStream *new_instance() = 0;
|
||||
virtual void subscribe(Mavlink *mavlink) = 0;
|
||||
virtual const char *get_name() = 0;
|
||||
};
|
||||
|
||||
|
||||
#endif /* MAVLINK_STREAM_H_ */
|
||||
@@ -1,6 +1,6 @@
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (C) 2012-2013 PX4 Development Team. All rights reserved.
|
||||
# Copyright (c) 2012-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
|
||||
@@ -36,10 +36,12 @@
|
||||
#
|
||||
|
||||
MODULE_COMMAND = mavlink
|
||||
SRCS += mavlink.c \
|
||||
mavlink_parameters.c \
|
||||
mavlink_receiver.cpp \
|
||||
orb_listener.c \
|
||||
waypoints.c
|
||||
SRCS += mavlink_main.cpp \
|
||||
mavlink.c \
|
||||
mavlink_receiver.cpp \
|
||||
mavlink_orb_subscription.cpp \
|
||||
mavlink_messages.cpp \
|
||||
mavlink_stream.cpp \
|
||||
mavlink_rate_limiter.cpp
|
||||
|
||||
INCLUDE_DIRS += $(MAVLINK_SRC)/include/mavlink
|
||||
|
||||
File diff suppressed because it is too large
Load Diff
@@ -1,7 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
* Author: @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
* Copyright (c) 2012-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
|
||||
|
||||
File diff suppressed because it is too large
Load Diff
@@ -1,9 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2008-2012 PX4 Development Team. All rights reserved.
|
||||
* Author: @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
* @author Thomas Gubler <thomasgubler@student.ethz.ch>
|
||||
* @author Julian Oes <joes@student.ethz.ch>
|
||||
* Copyright (c) 2009-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
|
||||
@@ -37,6 +34,11 @@
|
||||
/**
|
||||
* @file waypoints.h
|
||||
* MAVLink waypoint protocol definition (BSD-relicensed).
|
||||
*
|
||||
* @author Petri Tanskanen <petri.tanskanen@inf.ethz.ch>
|
||||
* @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
* @author Thomas Gubler <thomasgubler@student.ethz.ch>
|
||||
* @author Julian Oes <joes@student.ethz.ch>
|
||||
*/
|
||||
|
||||
#ifndef WAYPOINTS_H_
|
||||
@@ -106,7 +108,4 @@ extern void mavlink_missionlib_current_waypoint_changed(uint16_t index, float pa
|
||||
|
||||
static uint8_t missionlib_msg_buf[MAVLINK_MAX_PACKET_LEN];
|
||||
|
||||
void mavlink_missionlib_send_message(mavlink_message_t *msg);
|
||||
int mavlink_missionlib_send_gcs_string(const char *string);
|
||||
|
||||
#endif /* WAYPOINTS_H_ */
|
||||
|
||||
File diff suppressed because it is too large
Load Diff
@@ -1,344 +0,0 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
* Author: Lorenz Meier <lm@inf.ethz.ch>
|
||||
*
|
||||
* 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_receiver.c
|
||||
* MAVLink protocol message receive and dispatch
|
||||
*
|
||||
* @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
*/
|
||||
|
||||
/* XXX trim includes */
|
||||
#include <nuttx/config.h>
|
||||
#include <unistd.h>
|
||||
#include <pthread.h>
|
||||
#include <stdio.h>
|
||||
#include <math.h>
|
||||
#include <stdbool.h>
|
||||
#include <fcntl.h>
|
||||
#include <mqueue.h>
|
||||
#include <string.h>
|
||||
#include "mavlink_bridge_header.h"
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <time.h>
|
||||
#include <float.h>
|
||||
#include <unistd.h>
|
||||
#include <nuttx/sched.h>
|
||||
#include <sys/prctl.h>
|
||||
#include <termios.h>
|
||||
#include <errno.h>
|
||||
#include <stdlib.h>
|
||||
#include <poll.h>
|
||||
|
||||
#include <systemlib/param/param.h>
|
||||
#include <systemlib/systemlib.h>
|
||||
|
||||
#include "util.h"
|
||||
#include "orb_topics.h"
|
||||
|
||||
/* XXX should be in a header somewhere */
|
||||
pthread_t receive_start(int uart);
|
||||
|
||||
static void handle_message(mavlink_message_t *msg);
|
||||
static void *receive_thread(void *arg);
|
||||
|
||||
static mavlink_status_t status;
|
||||
static struct vehicle_vicon_position_s vicon_position;
|
||||
static struct vehicle_command_s vcmd;
|
||||
static struct offboard_control_setpoint_s offboard_control_sp;
|
||||
|
||||
struct vehicle_global_position_s hil_global_pos;
|
||||
struct vehicle_attitude_s hil_attitude;
|
||||
orb_advert_t pub_hil_global_pos = -1;
|
||||
orb_advert_t pub_hil_attitude = -1;
|
||||
|
||||
static orb_advert_t cmd_pub = -1;
|
||||
static orb_advert_t flow_pub = -1;
|
||||
|
||||
static orb_advert_t offboard_control_sp_pub = -1;
|
||||
static orb_advert_t vicon_position_pub = -1;
|
||||
|
||||
extern bool gcs_link;
|
||||
|
||||
static void
|
||||
handle_message(mavlink_message_t *msg)
|
||||
{
|
||||
if (msg->msgid == MAVLINK_MSG_ID_COMMAND_LONG) {
|
||||
|
||||
mavlink_command_long_t cmd_mavlink;
|
||||
mavlink_msg_command_long_decode(msg, &cmd_mavlink);
|
||||
|
||||
if (cmd_mavlink.target_system == mavlink_system.sysid && ((cmd_mavlink.target_component == mavlink_system.compid)
|
||||
|| (cmd_mavlink.target_component == MAV_COMP_ID_ALL))) {
|
||||
//check for MAVLINK terminate command
|
||||
if (cmd_mavlink.command == MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN && ((int)cmd_mavlink.param1) == 3) {
|
||||
/* This is the link shutdown command, terminate mavlink */
|
||||
warnx("terminating...");
|
||||
fflush(stdout);
|
||||
usleep(50000);
|
||||
|
||||
/* terminate other threads and this thread */
|
||||
thread_should_exit = true;
|
||||
|
||||
} else {
|
||||
|
||||
/* Copy the content of mavlink_command_long_t cmd_mavlink into command_t cmd */
|
||||
vcmd.param1 = cmd_mavlink.param1;
|
||||
vcmd.param2 = cmd_mavlink.param2;
|
||||
vcmd.param3 = cmd_mavlink.param3;
|
||||
vcmd.param4 = cmd_mavlink.param4;
|
||||
vcmd.param5 = cmd_mavlink.param5;
|
||||
vcmd.param6 = cmd_mavlink.param6;
|
||||
vcmd.param7 = cmd_mavlink.param7;
|
||||
vcmd.command = cmd_mavlink.command;
|
||||
vcmd.target_system = cmd_mavlink.target_system;
|
||||
vcmd.target_component = cmd_mavlink.target_component;
|
||||
vcmd.source_system = msg->sysid;
|
||||
vcmd.source_component = msg->compid;
|
||||
vcmd.confirmation = cmd_mavlink.confirmation;
|
||||
|
||||
/* check if topic is advertised */
|
||||
if (cmd_pub <= 0) {
|
||||
cmd_pub = orb_advertise(ORB_ID(vehicle_command), &vcmd);
|
||||
}
|
||||
|
||||
/* publish */
|
||||
orb_publish(ORB_ID(vehicle_command), cmd_pub, &vcmd);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
if (msg->msgid == MAVLINK_MSG_ID_OPTICAL_FLOW) {
|
||||
mavlink_optical_flow_t flow;
|
||||
mavlink_msg_optical_flow_decode(msg, &flow);
|
||||
|
||||
struct optical_flow_s f;
|
||||
|
||||
f.timestamp = hrt_absolute_time();
|
||||
f.flow_raw_x = flow.flow_x;
|
||||
f.flow_raw_y = flow.flow_y;
|
||||
f.flow_comp_x_m = flow.flow_comp_m_x;
|
||||
f.flow_comp_y_m = flow.flow_comp_m_y;
|
||||
f.ground_distance_m = flow.ground_distance;
|
||||
f.quality = flow.quality;
|
||||
f.sensor_id = flow.sensor_id;
|
||||
|
||||
/* check if topic is advertised */
|
||||
if (flow_pub <= 0) {
|
||||
flow_pub = orb_advertise(ORB_ID(optical_flow), &f);
|
||||
|
||||
} else {
|
||||
/* publish */
|
||||
orb_publish(ORB_ID(optical_flow), flow_pub, &f);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
if (msg->msgid == MAVLINK_MSG_ID_SET_MODE) {
|
||||
/* Set mode on request */
|
||||
mavlink_set_mode_t new_mode;
|
||||
mavlink_msg_set_mode_decode(msg, &new_mode);
|
||||
|
||||
/* Copy the content of mavlink_command_long_t cmd_mavlink into command_t cmd */
|
||||
vcmd.param1 = new_mode.base_mode;
|
||||
vcmd.param2 = new_mode.custom_mode;
|
||||
vcmd.param3 = 0;
|
||||
vcmd.param4 = 0;
|
||||
vcmd.param5 = 0;
|
||||
vcmd.param6 = 0;
|
||||
vcmd.param7 = 0;
|
||||
vcmd.command = MAV_CMD_DO_SET_MODE;
|
||||
vcmd.target_system = new_mode.target_system;
|
||||
vcmd.target_component = MAV_COMP_ID_ALL;
|
||||
vcmd.source_system = msg->sysid;
|
||||
vcmd.source_component = msg->compid;
|
||||
vcmd.confirmation = 1;
|
||||
|
||||
/* check if topic is advertised */
|
||||
if (cmd_pub <= 0) {
|
||||
cmd_pub = orb_advertise(ORB_ID(vehicle_command), &vcmd);
|
||||
|
||||
} else {
|
||||
/* create command */
|
||||
orb_publish(ORB_ID(vehicle_command), cmd_pub, &vcmd);
|
||||
}
|
||||
}
|
||||
|
||||
/* Handle Vicon position estimates */
|
||||
if (msg->msgid == MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE) {
|
||||
mavlink_vicon_position_estimate_t pos;
|
||||
mavlink_msg_vicon_position_estimate_decode(msg, &pos);
|
||||
|
||||
vicon_position.x = pos.x;
|
||||
vicon_position.y = pos.y;
|
||||
vicon_position.z = pos.z;
|
||||
|
||||
if (vicon_position_pub <= 0) {
|
||||
vicon_position_pub = orb_advertise(ORB_ID(vehicle_vicon_position), &vicon_position);
|
||||
|
||||
} else {
|
||||
orb_publish(ORB_ID(vehicle_vicon_position), vicon_position_pub, &vicon_position);
|
||||
}
|
||||
}
|
||||
|
||||
/* Handle quadrotor motor setpoints */
|
||||
|
||||
if (msg->msgid == MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST) {
|
||||
mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t quad_motors_setpoint;
|
||||
mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_decode(msg, &quad_motors_setpoint);
|
||||
|
||||
if (mavlink_system.sysid < 4) {
|
||||
|
||||
/* switch to a receiving link mode */
|
||||
gcs_link = false;
|
||||
|
||||
/*
|
||||
* rate control mode - defined by MAVLink
|
||||
*/
|
||||
|
||||
uint8_t ml_mode = 0;
|
||||
bool ml_armed = false;
|
||||
|
||||
switch (quad_motors_setpoint.mode) {
|
||||
case 0:
|
||||
ml_armed = false;
|
||||
break;
|
||||
|
||||
case 1:
|
||||
ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_RATES;
|
||||
ml_armed = true;
|
||||
|
||||
break;
|
||||
|
||||
case 2:
|
||||
ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE;
|
||||
ml_armed = true;
|
||||
|
||||
break;
|
||||
|
||||
case 3:
|
||||
ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY;
|
||||
break;
|
||||
|
||||
case 4:
|
||||
ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_POSITION;
|
||||
break;
|
||||
}
|
||||
|
||||
offboard_control_sp.p1 = (float)quad_motors_setpoint.roll[mavlink_system.sysid - 1] / (float)INT16_MAX;
|
||||
offboard_control_sp.p2 = (float)quad_motors_setpoint.pitch[mavlink_system.sysid - 1] / (float)INT16_MAX;
|
||||
offboard_control_sp.p3 = (float)quad_motors_setpoint.yaw[mavlink_system.sysid - 1] / (float)INT16_MAX;
|
||||
offboard_control_sp.p4 = (float)quad_motors_setpoint.thrust[mavlink_system.sysid - 1] / (float)UINT16_MAX;
|
||||
|
||||
if (quad_motors_setpoint.thrust[mavlink_system.sysid - 1] == 0) {
|
||||
ml_armed = false;
|
||||
}
|
||||
|
||||
offboard_control_sp.armed = ml_armed;
|
||||
offboard_control_sp.mode = ml_mode;
|
||||
|
||||
offboard_control_sp.timestamp = hrt_absolute_time();
|
||||
|
||||
/* check if topic has to be advertised */
|
||||
if (offboard_control_sp_pub <= 0) {
|
||||
offboard_control_sp_pub = orb_advertise(ORB_ID(offboard_control_setpoint), &offboard_control_sp);
|
||||
|
||||
} else {
|
||||
/* Publish */
|
||||
orb_publish(ORB_ID(offboard_control_setpoint), offboard_control_sp_pub, &offboard_control_sp);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Receive data from UART.
|
||||
*/
|
||||
static void *
|
||||
receive_thread(void *arg)
|
||||
{
|
||||
int uart_fd = *((int *)arg);
|
||||
|
||||
const int timeout = 1000;
|
||||
uint8_t buf[32];
|
||||
|
||||
mavlink_message_t msg;
|
||||
|
||||
prctl(PR_SET_NAME, "mavlink_onboard_rcv", getpid());
|
||||
|
||||
struct pollfd fds[] = { { .fd = uart_fd, .events = POLLIN } };
|
||||
|
||||
ssize_t nread = 0;
|
||||
|
||||
while (!thread_should_exit) {
|
||||
if (poll(fds, 1, timeout) > 0) {
|
||||
if (nread < sizeof(buf)) {
|
||||
/* to avoid reading very small chunks wait for data before reading */
|
||||
usleep(1000);
|
||||
}
|
||||
|
||||
/* non-blocking read. read may return negative values */
|
||||
nread = read(uart_fd, buf, sizeof(buf));
|
||||
|
||||
/* if read failed, this loop won't execute */
|
||||
for (ssize_t i = 0; i < nread; i++) {
|
||||
if (mavlink_parse_char(chan, buf[i], &msg, &status)) {
|
||||
/* handle generic messages and commands */
|
||||
handle_message(&msg);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
return NULL;
|
||||
}
|
||||
|
||||
pthread_t
|
||||
receive_start(int uart)
|
||||
{
|
||||
pthread_attr_t receiveloop_attr;
|
||||
pthread_attr_init(&receiveloop_attr);
|
||||
|
||||
struct sched_param param;
|
||||
param.sched_priority = SCHED_PRIORITY_MAX - 40;
|
||||
(void)pthread_attr_setschedparam(&receiveloop_attr, ¶m);
|
||||
|
||||
pthread_attr_setstacksize(&receiveloop_attr, 2048);
|
||||
|
||||
pthread_t thread;
|
||||
pthread_create(&thread, &receiveloop_attr, receive_thread, &uart);
|
||||
return thread;
|
||||
}
|
||||
@@ -1,42 +0,0 @@
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (C) 2012-2013 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.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
#
|
||||
# MAVLink protocol to uORB interface process (XXX hack for onboard use)
|
||||
#
|
||||
|
||||
MODULE_COMMAND = mavlink_onboard
|
||||
SRCS = mavlink.c \
|
||||
mavlink_receiver.c
|
||||
|
||||
INCLUDE_DIRS += $(MAVLINK_SRC)/include/mavlink
|
||||
@@ -1,102 +0,0 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2008-2012 PX4 Development Team. All rights reserved.
|
||||
* Author: @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
*
|
||||
* 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 orb_topics.h
|
||||
* Common sets of topics subscribed to or published by the MAVLink driver,
|
||||
* and structures maintained by those subscriptions.
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/sensor_combined.h>
|
||||
#include <uORB/topics/rc_channels.h>
|
||||
#include <uORB/topics/vehicle_attitude.h>
|
||||
#include <uORB/topics/vehicle_gps_position.h>
|
||||
#include <uORB/topics/vehicle_global_position.h>
|
||||
#include <uORB/topics/vehicle_status.h>
|
||||
#include <uORB/topics/offboard_control_setpoint.h>
|
||||
#include <uORB/topics/vehicle_command.h>
|
||||
#include <uORB/topics/vehicle_local_position_setpoint.h>
|
||||
#include <uORB/topics/vehicle_vicon_position.h>
|
||||
#include <uORB/topics/position_setpoint_triplet.h>
|
||||
#include <uORB/topics/vehicle_attitude_setpoint.h>
|
||||
#include <uORB/topics/vehicle_control_mode.h>
|
||||
#include <uORB/topics/optical_flow.h>
|
||||
#include <uORB/topics/actuator_outputs.h>
|
||||
#include <uORB/topics/actuator_controls.h>
|
||||
#include <uORB/topics/actuator_armed.h>
|
||||
#include <uORB/topics/manual_control_setpoint.h>
|
||||
#include <uORB/topics/debug_key_value.h>
|
||||
#include <drivers/drv_rc_input.h>
|
||||
|
||||
struct mavlink_subscriptions {
|
||||
int sensor_sub;
|
||||
int att_sub;
|
||||
int global_pos_sub;
|
||||
int act_0_sub;
|
||||
int act_1_sub;
|
||||
int act_2_sub;
|
||||
int act_3_sub;
|
||||
int gps_sub;
|
||||
int man_control_sp_sub;
|
||||
int safety_sub;
|
||||
int actuators_sub;
|
||||
int local_pos_sub;
|
||||
int spa_sub;
|
||||
int spl_sub;
|
||||
int spg_sub;
|
||||
int debug_key_value;
|
||||
int input_rc_sub;
|
||||
};
|
||||
|
||||
extern struct mavlink_subscriptions mavlink_subs;
|
||||
|
||||
/** Global position */
|
||||
extern struct vehicle_global_position_s global_pos;
|
||||
|
||||
/** Local position */
|
||||
extern struct vehicle_local_position_s local_pos;
|
||||
|
||||
/** Vehicle status */
|
||||
// extern struct vehicle_status_s v_status;
|
||||
|
||||
/** RC channels */
|
||||
extern struct rc_channels_s rc;
|
||||
|
||||
/** Actuator armed state */
|
||||
// extern struct actuator_armed_s armed;
|
||||
|
||||
/** Worker thread starter */
|
||||
extern pthread_t uorb_receive_start(void);
|
||||
@@ -65,7 +65,6 @@
|
||||
#include <uORB/topics/vehicle_global_position.h>
|
||||
#include <uORB/topics/home_position.h>
|
||||
#include <uORB/topics/position_setpoint_triplet.h>
|
||||
#include <uORB/topics/mission_result.h>
|
||||
#include <uORB/topics/vehicle_status.h>
|
||||
#include <uORB/topics/vehicle_control_mode.h>
|
||||
#include <uORB/topics/parameter_update.h>
|
||||
@@ -288,9 +287,9 @@ private:
|
||||
static void task_main_trampoline(int argc, char *argv[]);
|
||||
|
||||
/**
|
||||
* Main sensor collection task.
|
||||
* Main task.
|
||||
*/
|
||||
void task_main() __attribute__((noreturn));
|
||||
void task_main();
|
||||
|
||||
void publish_safepoints(unsigned points);
|
||||
|
||||
@@ -395,7 +394,6 @@ Navigator::Navigator() :
|
||||
|
||||
/* publications */
|
||||
_pos_sp_triplet_pub(-1),
|
||||
_mission_result_pub(-1),
|
||||
|
||||
/* performance counters */
|
||||
_loop_perf(perf_alloc(PC_ELAPSED, "navigator")),
|
||||
@@ -427,7 +425,6 @@ Navigator::Navigator() :
|
||||
_parameter_handles.rtl_land_delay = param_find("NAV_RTL_LAND_T");
|
||||
|
||||
memset(&_pos_sp_triplet, 0, sizeof(struct position_setpoint_triplet_s));
|
||||
memset(&_mission_result, 0, sizeof(struct mission_result_s));
|
||||
memset(&_mission_item, 0, sizeof(struct mission_item_s));
|
||||
|
||||
memset(&nav_states_str, 0, sizeof(nav_states_str));
|
||||
@@ -529,13 +526,16 @@ Navigator::offboard_mission_update(bool isrotaryWing)
|
||||
missionFeasiblityChecker.checkMissionFeasible(isrotaryWing, dm_current, (size_t)offboard_mission.count, _geofence);
|
||||
|
||||
_mission.set_offboard_dataman_id(offboard_mission.dataman_id);
|
||||
_mission.set_current_offboard_mission_index(offboard_mission.current_index);
|
||||
|
||||
_mission.set_offboard_mission_count(offboard_mission.count);
|
||||
_mission.set_current_offboard_mission_index(offboard_mission.current_index);
|
||||
|
||||
} else {
|
||||
_mission.set_current_offboard_mission_index(0);
|
||||
_mission.set_offboard_mission_count(0);
|
||||
_mission.set_current_offboard_mission_index(0);
|
||||
}
|
||||
|
||||
_mission.publish_mission_result();
|
||||
}
|
||||
|
||||
void
|
||||
@@ -545,12 +545,12 @@ Navigator::onboard_mission_update()
|
||||
|
||||
if (orb_copy(ORB_ID(mission), _onboard_mission_sub, &onboard_mission) == OK) {
|
||||
|
||||
_mission.set_current_onboard_mission_index(onboard_mission.current_index);
|
||||
_mission.set_onboard_mission_count(onboard_mission.count);
|
||||
_mission.set_current_onboard_mission_index(onboard_mission.current_index);
|
||||
|
||||
} else {
|
||||
_mission.set_current_onboard_mission_index(0);
|
||||
_mission.set_onboard_mission_count(0);
|
||||
_mission.set_current_onboard_mission_index(0);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -1112,6 +1112,8 @@ Navigator::set_mission_item()
|
||||
ret = _mission.get_current_mission_item(&_mission_item, &onboard, &index);
|
||||
|
||||
if (ret == OK) {
|
||||
_mission.report_current_offboard_mission_item();
|
||||
|
||||
_mission_item_valid = true;
|
||||
position_setpoint_from_mission_item(&_pos_sp_triplet.current, &_mission_item);
|
||||
|
||||
@@ -1581,6 +1583,9 @@ void
|
||||
Navigator::on_mission_item_reached()
|
||||
{
|
||||
if (myState == NAV_STATE_MISSION) {
|
||||
|
||||
_mission.report_mission_item_reached();
|
||||
|
||||
if (_do_takeoff) {
|
||||
/* takeoff completed */
|
||||
_do_takeoff = false;
|
||||
@@ -1627,6 +1632,7 @@ Navigator::on_mission_item_reached()
|
||||
mavlink_log_info(_mavlink_fd, "[navigator] landing completed");
|
||||
dispatch(EVENT_READY_REQUESTED);
|
||||
}
|
||||
_mission.publish_mission_result();
|
||||
}
|
||||
|
||||
void
|
||||
|
||||
@@ -36,13 +36,12 @@
|
||||
* Helper class to access missions
|
||||
*/
|
||||
|
||||
// #include <stdio.h>
|
||||
// #include <stdlib.h>
|
||||
// #include <string.h>
|
||||
// #include <unistd.h>
|
||||
|
||||
#include <string.h>
|
||||
#include <stdlib.h>
|
||||
#include <dataman/dataman.h>
|
||||
#include <systemlib/err.h>
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/mission_result.h>
|
||||
#include "navigator_mission.h"
|
||||
|
||||
/* oddly, ERROR is not defined for c++ */
|
||||
@@ -60,8 +59,11 @@ Mission::Mission() :
|
||||
_offboard_mission_item_count(0),
|
||||
_onboard_mission_item_count(0),
|
||||
_onboard_mission_allowed(false),
|
||||
_current_mission_type(MISSION_TYPE_NONE)
|
||||
{}
|
||||
_current_mission_type(MISSION_TYPE_NONE),
|
||||
_mission_result_pub(-1)
|
||||
{
|
||||
memset(&_mission_result, 0, sizeof(struct mission_result_s));
|
||||
}
|
||||
|
||||
Mission::~Mission()
|
||||
{
|
||||
@@ -78,8 +80,16 @@ void
|
||||
Mission::set_current_offboard_mission_index(int new_index)
|
||||
{
|
||||
if (new_index != -1) {
|
||||
warnx("specifically set to %d", new_index);
|
||||
_current_offboard_mission_index = (unsigned)new_index;
|
||||
} else {
|
||||
|
||||
/* if less WPs available, reset to first WP */
|
||||
if (_current_offboard_mission_index >= _offboard_mission_item_count) {
|
||||
_current_offboard_mission_index = 0;
|
||||
}
|
||||
}
|
||||
report_current_offboard_mission_item();
|
||||
}
|
||||
|
||||
void
|
||||
@@ -87,7 +97,15 @@ Mission::set_current_onboard_mission_index(int new_index)
|
||||
{
|
||||
if (new_index != -1) {
|
||||
_current_onboard_mission_index = (unsigned)new_index;
|
||||
} else {
|
||||
|
||||
/* if less WPs available, reset to first WP */
|
||||
if (_current_onboard_mission_index >= _onboard_mission_item_count) {
|
||||
_current_onboard_mission_index = 0;
|
||||
}
|
||||
}
|
||||
// TODO: implement this for onboard missions as well
|
||||
// report_current_mission_item();
|
||||
}
|
||||
|
||||
void
|
||||
@@ -267,3 +285,34 @@ Mission::move_to_next()
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
Mission::report_mission_item_reached()
|
||||
{
|
||||
if (_current_mission_type == MISSION_TYPE_OFFBOARD) {
|
||||
_mission_result.mission_reached = true;
|
||||
_mission_result.mission_index_reached = _current_offboard_mission_index;
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
Mission::report_current_offboard_mission_item()
|
||||
{
|
||||
_mission_result.index_current_mission = _current_offboard_mission_index;
|
||||
}
|
||||
|
||||
void
|
||||
Mission::publish_mission_result()
|
||||
{
|
||||
/* lazily publish the mission result only once available */
|
||||
if (_mission_result_pub > 0) {
|
||||
/* publish mission result */
|
||||
orb_publish(ORB_ID(mission_result), _mission_result_pub, &_mission_result);
|
||||
|
||||
} else {
|
||||
/* advertise and publish */
|
||||
_mission_result_pub = orb_advertise(ORB_ID(mission_result), &_mission_result);
|
||||
}
|
||||
/* reset reached bool */
|
||||
_mission_result.mission_reached = false;
|
||||
}
|
||||
|
||||
@@ -40,6 +40,7 @@
|
||||
#define NAVIGATOR_MISSION_H
|
||||
|
||||
#include <uORB/topics/mission.h>
|
||||
#include <uORB/topics/mission_result.h>
|
||||
|
||||
|
||||
class __EXPORT Mission
|
||||
@@ -71,7 +72,9 @@ public:
|
||||
|
||||
void move_to_next();
|
||||
|
||||
void add_home_pos(struct mission_item_s *new_mission_item);
|
||||
void report_mission_item_reached();
|
||||
void report_current_offboard_mission_item();
|
||||
void publish_mission_result();
|
||||
|
||||
private:
|
||||
bool current_onboard_mission_available();
|
||||
@@ -92,6 +95,10 @@ private:
|
||||
MISSION_TYPE_ONBOARD,
|
||||
MISSION_TYPE_OFFBOARD,
|
||||
} _current_mission_type;
|
||||
|
||||
int _mission_result_pub;
|
||||
|
||||
struct mission_result_s _mission_result;
|
||||
};
|
||||
|
||||
#endif
|
||||
@@ -54,7 +54,8 @@
|
||||
struct mission_result_s
|
||||
{
|
||||
bool mission_reached; /**< true if mission has been reached */
|
||||
unsigned mission_index; /**< index of the mission which has been reached */
|
||||
unsigned mission_index_reached; /**< index of the mission which has been reached */
|
||||
unsigned index_current_mission; /**< index of the current mission */
|
||||
};
|
||||
|
||||
/**
|
||||
|
||||
@@ -76,7 +76,7 @@ struct vehicle_attitude_s {
|
||||
float rate_offsets[3]; /**< Offsets of the body angular rates from zero */
|
||||
float R[3][3]; /**< Rotation matrix body to world, (Tait-Bryan, NED) */
|
||||
float q[4]; /**< Quaternion (NED) */
|
||||
float g_comp[3]; /**< Compensated gravity vector */
|
||||
float g_comp[3]; /**< Compensated gravity vector */
|
||||
bool R_valid; /**< Rotation matrix valid */
|
||||
bool q_valid; /**< Quaternion valid */
|
||||
|
||||
|
||||
Reference in New Issue
Block a user