forked from Archive/PX4-Autopilot
Merge remote-tracking branch 'origin/master' into offset_tuning
This commit is contained in:
commit
93a38a1e7c
|
@ -50,7 +50,7 @@
|
||||||
|
|
||||||
__BEGIN_DECLS
|
__BEGIN_DECLS
|
||||||
|
|
||||||
#include "geo/geo_mag_declination.h"
|
#include "geo_mag_declination.h"
|
||||||
|
|
||||||
#include <stdbool.h>
|
#include <stdbool.h>
|
||||||
|
|
||||||
|
|
|
@ -65,6 +65,7 @@
|
||||||
#include <drivers/drv_hrt.h>
|
#include <drivers/drv_hrt.h>
|
||||||
|
|
||||||
#include <lib/mathlib/mathlib.h>
|
#include <lib/mathlib/mathlib.h>
|
||||||
|
#include <lib/geo/geo.h>
|
||||||
|
|
||||||
#include <systemlib/systemlib.h>
|
#include <systemlib/systemlib.h>
|
||||||
#include <systemlib/perf_counter.h>
|
#include <systemlib/perf_counter.h>
|
||||||
|
@ -287,6 +288,9 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
|
||||||
|
|
||||||
float gyro_offsets[3] = { 0.0f, 0.0f, 0.0f };
|
float gyro_offsets[3] = { 0.0f, 0.0f, 0.0f };
|
||||||
|
|
||||||
|
/* magnetic declination, in radians */
|
||||||
|
float mag_decl = 0.0f;
|
||||||
|
|
||||||
/* rotation matrix for magnetic declination */
|
/* rotation matrix for magnetic declination */
|
||||||
math::Matrix<3, 3> R_decl;
|
math::Matrix<3, 3> R_decl;
|
||||||
R_decl.identity();
|
R_decl.identity();
|
||||||
|
@ -325,9 +329,6 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
|
||||||
|
|
||||||
/* update parameters */
|
/* update parameters */
|
||||||
parameters_update(&ekf_param_handles, &ekf_params);
|
parameters_update(&ekf_param_handles, &ekf_params);
|
||||||
|
|
||||||
/* update mag declination rotation matrix */
|
|
||||||
R_decl.from_euler(0.0f, 0.0f, ekf_params.mag_decl);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/* only run filter if sensor values changed */
|
/* only run filter if sensor values changed */
|
||||||
|
@ -340,6 +341,13 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
|
||||||
orb_check(sub_gps, &gps_updated);
|
orb_check(sub_gps, &gps_updated);
|
||||||
if (gps_updated) {
|
if (gps_updated) {
|
||||||
orb_copy(ORB_ID(vehicle_gps_position), sub_gps, &gps);
|
orb_copy(ORB_ID(vehicle_gps_position), sub_gps, &gps);
|
||||||
|
|
||||||
|
if (gps.eph_m < 20.0f && hrt_elapsed_time(&gps.timestamp_position) < 1000000) {
|
||||||
|
mag_decl = math::radians(get_mag_declination(gps.lat / 1e7f, gps.lon / 1e7f));
|
||||||
|
|
||||||
|
/* update mag declination rotation matrix */
|
||||||
|
R_decl.from_euler(0.0f, 0.0f, mag_decl);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
bool global_pos_updated;
|
bool global_pos_updated;
|
||||||
|
@ -469,7 +477,15 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
|
||||||
parameters_update(&ekf_param_handles, &ekf_params);
|
parameters_update(&ekf_param_handles, &ekf_params);
|
||||||
|
|
||||||
/* update mag declination rotation matrix */
|
/* update mag declination rotation matrix */
|
||||||
R_decl.from_euler(0.0f, 0.0f, ekf_params.mag_decl);
|
if (gps.eph_m < 20.0f && hrt_elapsed_time(&gps.timestamp_position) < 1000000) {
|
||||||
|
mag_decl = math::radians(get_mag_declination(gps.lat / 1e7f, gps.lon / 1e7f));
|
||||||
|
|
||||||
|
} else {
|
||||||
|
mag_decl = ekf_params.mag_decl;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* update mag declination rotation matrix */
|
||||||
|
R_decl.from_euler(0.0f, 0.0f, mag_decl);
|
||||||
|
|
||||||
x_aposteriori_k[0] = z_k[0];
|
x_aposteriori_k[0] = z_k[0];
|
||||||
x_aposteriori_k[1] = z_k[1];
|
x_aposteriori_k[1] = z_k[1];
|
||||||
|
@ -515,7 +531,7 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
|
||||||
|
|
||||||
att.roll = euler[0];
|
att.roll = euler[0];
|
||||||
att.pitch = euler[1];
|
att.pitch = euler[1];
|
||||||
att.yaw = euler[2] + ekf_params.mag_decl;
|
att.yaw = euler[2] + mag_decl;
|
||||||
|
|
||||||
att.rollspeed = x_aposteriori[0];
|
att.rollspeed = x_aposteriori[0];
|
||||||
att.pitchspeed = x_aposteriori[1];
|
att.pitchspeed = x_aposteriori[1];
|
||||||
|
|
|
@ -40,34 +40,31 @@
|
||||||
|
|
||||||
#include "mavlink_commands.h"
|
#include "mavlink_commands.h"
|
||||||
|
|
||||||
MavlinkCommandsStream::MavlinkCommandsStream(Mavlink *mavlink, mavlink_channel_t channel) : _channel(channel)
|
MavlinkCommandsStream::MavlinkCommandsStream(Mavlink *mavlink, mavlink_channel_t channel) : _channel(channel), _cmd_time(0)
|
||||||
{
|
{
|
||||||
_cmd_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_command));
|
_cmd_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_command));
|
||||||
_cmd = (struct vehicle_command_s *)_cmd_sub->get_data();
|
|
||||||
}
|
|
||||||
|
|
||||||
MavlinkCommandsStream::~MavlinkCommandsStream()
|
|
||||||
{
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void
|
void
|
||||||
MavlinkCommandsStream::update(const hrt_abstime t)
|
MavlinkCommandsStream::update(const hrt_abstime t)
|
||||||
{
|
{
|
||||||
if (_cmd_sub->update(t)) {
|
struct vehicle_command_s cmd;
|
||||||
|
|
||||||
|
if (_cmd_sub->update(&_cmd_time, &cmd)) {
|
||||||
/* only send commands for other systems/components */
|
/* only send commands for other systems/components */
|
||||||
if (_cmd->target_system != mavlink_system.sysid || _cmd->target_component != mavlink_system.compid) {
|
if (cmd.target_system != mavlink_system.sysid || cmd.target_component != mavlink_system.compid) {
|
||||||
mavlink_msg_command_long_send(_channel,
|
mavlink_msg_command_long_send(_channel,
|
||||||
_cmd->target_system,
|
cmd.target_system,
|
||||||
_cmd->target_component,
|
cmd.target_component,
|
||||||
_cmd->command,
|
cmd.command,
|
||||||
_cmd->confirmation,
|
cmd.confirmation,
|
||||||
_cmd->param1,
|
cmd.param1,
|
||||||
_cmd->param2,
|
cmd.param2,
|
||||||
_cmd->param3,
|
cmd.param3,
|
||||||
_cmd->param4,
|
cmd.param4,
|
||||||
_cmd->param5,
|
cmd.param5,
|
||||||
_cmd->param6,
|
cmd.param6,
|
||||||
_cmd->param7);
|
cmd.param7);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -55,10 +55,10 @@ private:
|
||||||
MavlinkOrbSubscription *_cmd_sub;
|
MavlinkOrbSubscription *_cmd_sub;
|
||||||
struct vehicle_command_s *_cmd;
|
struct vehicle_command_s *_cmd;
|
||||||
mavlink_channel_t _channel;
|
mavlink_channel_t _channel;
|
||||||
|
uint64_t _cmd_time;
|
||||||
|
|
||||||
public:
|
public:
|
||||||
MavlinkCommandsStream(Mavlink *mavlink, mavlink_channel_t channel);
|
MavlinkCommandsStream(Mavlink *mavlink, mavlink_channel_t channel);
|
||||||
~MavlinkCommandsStream();
|
|
||||||
void update(const hrt_abstime t);
|
void update(const hrt_abstime t);
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
|
@ -236,6 +236,12 @@ Mavlink::Mavlink() :
|
||||||
_subscribe_to_stream_rate(0.0f),
|
_subscribe_to_stream_rate(0.0f),
|
||||||
_flow_control_enabled(true),
|
_flow_control_enabled(true),
|
||||||
_message_buffer({}),
|
_message_buffer({}),
|
||||||
|
_param_initialized(false),
|
||||||
|
_param_system_id(0),
|
||||||
|
_param_component_id(0),
|
||||||
|
_param_system_type(0),
|
||||||
|
_param_use_hil_gps(0),
|
||||||
|
|
||||||
/* performance counters */
|
/* performance counters */
|
||||||
_loop_perf(perf_alloc(PC_ELAPSED, "mavlink"))
|
_loop_perf(perf_alloc(PC_ELAPSED, "mavlink"))
|
||||||
{
|
{
|
||||||
|
@ -494,44 +500,39 @@ Mavlink::mavlink_dev_ioctl(struct file *filep, int cmd, unsigned long arg)
|
||||||
|
|
||||||
void Mavlink::mavlink_update_system(void)
|
void Mavlink::mavlink_update_system(void)
|
||||||
{
|
{
|
||||||
static bool initialized = false;
|
|
||||||
static param_t param_system_id;
|
|
||||||
static param_t param_component_id;
|
|
||||||
static param_t param_system_type;
|
|
||||||
static param_t param_use_hil_gps;
|
|
||||||
|
|
||||||
if (!initialized) {
|
if (!_param_initialized) {
|
||||||
param_system_id = param_find("MAV_SYS_ID");
|
_param_system_id = param_find("MAV_SYS_ID");
|
||||||
param_component_id = param_find("MAV_COMP_ID");
|
_param_component_id = param_find("MAV_COMP_ID");
|
||||||
param_system_type = param_find("MAV_TYPE");
|
_param_system_type = param_find("MAV_TYPE");
|
||||||
param_use_hil_gps = param_find("MAV_USEHILGPS");
|
_param_use_hil_gps = param_find("MAV_USEHILGPS");
|
||||||
initialized = true;
|
_param_initialized = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
/* update system and component id */
|
/* update system and component id */
|
||||||
int32_t system_id;
|
int32_t system_id;
|
||||||
param_get(param_system_id, &system_id);
|
param_get(_param_system_id, &system_id);
|
||||||
|
|
||||||
if (system_id > 0 && system_id < 255) {
|
if (system_id > 0 && system_id < 255) {
|
||||||
mavlink_system.sysid = system_id;
|
mavlink_system.sysid = system_id;
|
||||||
}
|
}
|
||||||
|
|
||||||
int32_t component_id;
|
int32_t component_id;
|
||||||
param_get(param_component_id, &component_id);
|
param_get(_param_component_id, &component_id);
|
||||||
|
|
||||||
if (component_id > 0 && component_id < 255) {
|
if (component_id > 0 && component_id < 255) {
|
||||||
mavlink_system.compid = component_id;
|
mavlink_system.compid = component_id;
|
||||||
}
|
}
|
||||||
|
|
||||||
int32_t system_type;
|
int32_t system_type;
|
||||||
param_get(param_system_type, &system_type);
|
param_get(_param_system_type, &system_type);
|
||||||
|
|
||||||
if (system_type >= 0 && system_type < MAV_TYPE_ENUM_END) {
|
if (system_type >= 0 && system_type < MAV_TYPE_ENUM_END) {
|
||||||
mavlink_system.type = system_type;
|
mavlink_system.type = system_type;
|
||||||
}
|
}
|
||||||
|
|
||||||
int32_t use_hil_gps;
|
int32_t use_hil_gps;
|
||||||
param_get(param_use_hil_gps, &use_hil_gps);
|
param_get(_param_use_hil_gps, &use_hil_gps);
|
||||||
|
|
||||||
_use_hil_gps = (bool)use_hil_gps;
|
_use_hil_gps = (bool)use_hil_gps;
|
||||||
}
|
}
|
||||||
|
@ -819,7 +820,7 @@ void Mavlink::mavlink_pm_message_handler(const mavlink_channel_t chan, const mav
|
||||||
|
|
||||||
if (param == PARAM_INVALID) {
|
if (param == PARAM_INVALID) {
|
||||||
char buf[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN];
|
char buf[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN];
|
||||||
sprintf(buf, "[mavlink pm] unknown: %s", name);
|
sprintf(buf, "[pm] unknown: %s", name);
|
||||||
mavlink_missionlib_send_gcs_string(buf);
|
mavlink_missionlib_send_gcs_string(buf);
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
|
@ -1008,8 +1009,6 @@ void Mavlink::mavlink_wpm_send_waypoint_current(uint16_t seq)
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
mavlink_missionlib_send_gcs_string("ERROR: wp index out of bounds");
|
mavlink_missionlib_send_gcs_string("ERROR: wp index out of bounds");
|
||||||
|
|
||||||
if (_verbose) { warnx("ERROR: index out of bounds"); }
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1082,8 +1081,6 @@ void Mavlink::mavlink_wpm_send_waypoint_request(uint8_t sysid, uint8_t compid, u
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
mavlink_missionlib_send_gcs_string("ERROR: Waypoint index exceeds list capacity");
|
mavlink_missionlib_send_gcs_string("ERROR: Waypoint index exceeds list capacity");
|
||||||
|
|
||||||
if (_verbose) { warnx("ERROR: Waypoint index exceeds list capacity"); }
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1114,8 +1111,6 @@ void Mavlink::mavlink_waypoint_eventloop(uint64_t now)
|
||||||
|
|
||||||
mavlink_missionlib_send_gcs_string("Operation timeout");
|
mavlink_missionlib_send_gcs_string("Operation timeout");
|
||||||
|
|
||||||
if (_verbose) { warnx("Last operation (state=%u) timed out, changing state to MAVLINK_WPM_STATE_IDLE", _wpm->current_state); }
|
|
||||||
|
|
||||||
_wpm->current_state = MAVLINK_WPM_STATE_IDLE;
|
_wpm->current_state = MAVLINK_WPM_STATE_IDLE;
|
||||||
_wpm->current_partner_sysid = 0;
|
_wpm->current_partner_sysid = 0;
|
||||||
_wpm->current_partner_compid = 0;
|
_wpm->current_partner_compid = 0;
|
||||||
|
@ -1150,8 +1145,6 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg)
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
mavlink_missionlib_send_gcs_string("REJ. WP CMD: curr partner id mismatch");
|
mavlink_missionlib_send_gcs_string("REJ. WP CMD: curr partner id mismatch");
|
||||||
|
|
||||||
if (_verbose) { warnx("REJ. WP CMD: curr partner id mismatch"); }
|
|
||||||
}
|
}
|
||||||
|
|
||||||
break;
|
break;
|
||||||
|
@ -1175,15 +1168,10 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg)
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
mavlink_missionlib_send_gcs_string("IGN WP CURR CMD: Not in list");
|
mavlink_missionlib_send_gcs_string("IGN WP CURR CMD: Not in list");
|
||||||
|
|
||||||
if (_verbose) { warnx("IGN WP CURR CMD: Not in list"); }
|
|
||||||
}
|
}
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
mavlink_missionlib_send_gcs_string("IGN WP CURR CMD: Busy");
|
mavlink_missionlib_send_gcs_string("IGN WP CURR CMD: Busy");
|
||||||
|
|
||||||
if (_verbose) { warnx("IGN WP CURR CMD: Busy"); }
|
|
||||||
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1214,8 +1202,6 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg)
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
mavlink_missionlib_send_gcs_string("IGN REQUEST LIST: Busy");
|
mavlink_missionlib_send_gcs_string("IGN REQUEST LIST: Busy");
|
||||||
|
|
||||||
if (_verbose) { warnx("IGN REQUEST LIST: Busy"); }
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1233,8 +1219,6 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg)
|
||||||
|
|
||||||
mavlink_missionlib_send_gcs_string("REJ. WP CMD: Req. WP not in list");
|
mavlink_missionlib_send_gcs_string("REJ. WP CMD: Req. WP not in list");
|
||||||
|
|
||||||
if (_verbose) { warnx("Ignored MAVLINK_MSG_ID_MISSION_ITEM_REQUEST because the requested waypoint ID (%u) was out of bounds.", wpr.seq); }
|
|
||||||
|
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1245,15 +1229,13 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg)
|
||||||
if (_wpm->current_state == MAVLINK_WPM_STATE_SENDLIST) {
|
if (_wpm->current_state == MAVLINK_WPM_STATE_SENDLIST) {
|
||||||
|
|
||||||
if (wpr.seq == 0) {
|
if (wpr.seq == 0) {
|
||||||
if (_verbose) { warnx("Got MAVLINK_MSG_ID_MISSION_ITEM_REQUEST of waypoint %u from %u changing state to MAVLINK_WPM_STATE_SENDLIST_SENDWPS", wpr.seq, msg->sysid); }
|
if (_verbose) { warnx("Got ITEM_REQUEST of waypoint %u from %u changing to STATE_SENDLIST_SENDWPS", wpr.seq, msg->sysid); }
|
||||||
|
|
||||||
_wpm->current_state = MAVLINK_WPM_STATE_SENDLIST_SENDWPS;
|
_wpm->current_state = MAVLINK_WPM_STATE_SENDLIST_SENDWPS;
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
mavlink_missionlib_send_gcs_string("REJ. WP CMD: First id != 0");
|
mavlink_missionlib_send_gcs_string("REJ. WP CMD: First id != 0");
|
||||||
|
|
||||||
if (_verbose) { warnx("REJ. WP CMD: First id != 0"); }
|
|
||||||
|
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1261,17 +1243,15 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg)
|
||||||
|
|
||||||
if (wpr.seq == _wpm->current_wp_id) {
|
if (wpr.seq == _wpm->current_wp_id) {
|
||||||
|
|
||||||
if (_verbose) { warnx("Got MAVLINK_MSG_ID_MISSION_ITEM_REQUEST of waypoint %u (again) from %u staying in state MAVLINK_WPM_STATE_SENDLIST_SENDWPS", wpr.seq, msg->sysid); }
|
if (_verbose) { warnx("Got ITEM_REQUEST of waypoint %u (again) from %u staying in STATE_SENDLIST_SENDWPS", wpr.seq, msg->sysid); }
|
||||||
|
|
||||||
} else if (wpr.seq == _wpm->current_wp_id + 1) {
|
} else if (wpr.seq == _wpm->current_wp_id + 1) {
|
||||||
|
|
||||||
if (_verbose) { warnx("Got MAVLINK_MSG_ID_MISSION_ITEM_REQUEST of waypoint %u from %u staying in state MAVLINK_WPM_STATE_SENDLIST_SENDWPS", wpr.seq, msg->sysid); }
|
if (_verbose) { warnx("Got ITEM_REQUEST of waypoint %u from %u staying in STATE_SENDLIST_SENDWPS", wpr.seq, msg->sysid); }
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
mavlink_missionlib_send_gcs_string("REJ. WP CMD: Req. WP was unexpected");
|
mavlink_missionlib_send_gcs_string("REJ. WP CMD: Req. WP was unexpected");
|
||||||
|
|
||||||
if (_verbose) { warnx("Ignored MAVLINK_MSG_ID_MISSION_ITEM_REQUEST because the requested waypoint ID (%u) was not the expected (%u or %u).", wpr.seq, _wpm->current_wp_id, _wpm->current_wp_id + 1); }
|
|
||||||
|
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1279,8 +1259,6 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg)
|
||||||
|
|
||||||
mavlink_missionlib_send_gcs_string("REJ. WP CMD: Busy");
|
mavlink_missionlib_send_gcs_string("REJ. WP CMD: Busy");
|
||||||
|
|
||||||
if (_verbose) { warnx("Ignored MAVLINK_MSG_ID_MISSION_ITEM_REQUEST because i'm doing something else already (state=%i).", _wpm->current_state); }
|
|
||||||
|
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1294,7 +1272,7 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg)
|
||||||
} else {
|
} else {
|
||||||
mavlink_wpm_send_waypoint_ack(_wpm->current_partner_sysid, _wpm->current_partner_compid, MAV_MISSION_ERROR);
|
mavlink_wpm_send_waypoint_ack(_wpm->current_partner_sysid, _wpm->current_partner_compid, MAV_MISSION_ERROR);
|
||||||
|
|
||||||
if (_verbose) { warnx("ERROR: Waypoint %u out of bounds", wpr.seq); }
|
mavlink_missionlib_send_gcs_string("ERROR: Waypoint out of bounds");
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
@ -1328,15 +1306,11 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg)
|
||||||
}
|
}
|
||||||
|
|
||||||
if (wpc.count == 0) {
|
if (wpc.count == 0) {
|
||||||
mavlink_missionlib_send_gcs_string("COUNT 0");
|
mavlink_missionlib_send_gcs_string("WP COUNT 0");
|
||||||
|
|
||||||
if (_verbose) { warnx("got waypoint count of 0, clearing waypoint list and staying in state MAVLINK_WPM_STATE_IDLE"); }
|
|
||||||
|
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (_verbose) { warnx("Got MAVLINK_MSG_ID_MISSION_ITEM_COUNT (%u) from %u changing state to MAVLINK_WPM_STATE_GETLIST", wpc.count, msg->sysid); }
|
|
||||||
|
|
||||||
_wpm->current_state = MAVLINK_WPM_STATE_GETLIST;
|
_wpm->current_state = MAVLINK_WPM_STATE_GETLIST;
|
||||||
_wpm->current_wp_id = 0;
|
_wpm->current_wp_id = 0;
|
||||||
_wpm->current_partner_sysid = msg->sysid;
|
_wpm->current_partner_sysid = msg->sysid;
|
||||||
|
@ -1350,18 +1324,12 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg)
|
||||||
if (_wpm->current_wp_id == 0) {
|
if (_wpm->current_wp_id == 0) {
|
||||||
mavlink_missionlib_send_gcs_string("WP CMD OK AGAIN");
|
mavlink_missionlib_send_gcs_string("WP CMD OK AGAIN");
|
||||||
|
|
||||||
if (_verbose) { warnx("Got MAVLINK_MSG_ID_MISSION_ITEM_COUNT (%u) again from %u", wpc.count, msg->sysid); }
|
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
mavlink_missionlib_send_gcs_string("REJ. WP CMD: Busy");
|
mavlink_missionlib_send_gcs_string("REJ. WP CMD: Busy with WP");
|
||||||
|
|
||||||
if (_verbose) { warnx("Ignored MAVLINK_MSG_ID_MISSION_ITEM_COUNT because i'm already receiving waypoint %u.", _wpm->current_wp_id); }
|
|
||||||
}
|
}
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
mavlink_missionlib_send_gcs_string("IGN MISSION_COUNT CMD: Busy");
|
mavlink_missionlib_send_gcs_string("IGN MISSION_COUNT CMD: Busy");
|
||||||
|
|
||||||
if (_verbose) { warnx("IGN MISSION_COUNT CMD: Busy"); }
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -1384,7 +1352,6 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg)
|
||||||
|
|
||||||
if (wp.seq != 0) {
|
if (wp.seq != 0) {
|
||||||
mavlink_missionlib_send_gcs_string("Ignored MISSION_ITEM WP not 0");
|
mavlink_missionlib_send_gcs_string("Ignored MISSION_ITEM WP not 0");
|
||||||
warnx("Ignored MAVLINK_MSG_ID_MISSION_ITEM because the first waypoint ID (%u) was not 0.", wp.seq);
|
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1392,12 +1359,11 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg)
|
||||||
|
|
||||||
if (wp.seq >= _wpm->current_count) {
|
if (wp.seq >= _wpm->current_count) {
|
||||||
mavlink_missionlib_send_gcs_string("Ignored MISSION_ITEM WP out of bounds");
|
mavlink_missionlib_send_gcs_string("Ignored MISSION_ITEM WP out of bounds");
|
||||||
warnx("Ignored MAVLINK_MSG_ID_MISSION_ITEM because the waypoint ID (%u) was out of bounds.", wp.seq);
|
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (wp.seq != _wpm->current_wp_id) {
|
if (wp.seq != _wpm->current_wp_id) {
|
||||||
warnx("Ignored MAVLINK_MSG_ID_MISSION_ITEM because the waypoint ID (%u) was not the expected %u.", wp.seq, _wpm->current_wp_id);
|
mavlink_missionlib_send_gcs_string("IGN: waypoint ID mismatch");
|
||||||
mavlink_wpm_send_waypoint_request(_wpm->current_partner_sysid, _wpm->current_partner_compid, _wpm->current_wp_id);
|
mavlink_wpm_send_waypoint_request(_wpm->current_partner_sysid, _wpm->current_partner_compid, _wpm->current_wp_id);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
@ -1512,11 +1478,10 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg)
|
||||||
void
|
void
|
||||||
Mavlink::mavlink_missionlib_send_message(mavlink_message_t *msg)
|
Mavlink::mavlink_missionlib_send_message(mavlink_message_t *msg)
|
||||||
{
|
{
|
||||||
uint8_t missionlib_msg_buf[MAVLINK_MAX_PACKET_LEN];
|
uint8_t buf[MAVLINK_MAX_PACKET_LEN];
|
||||||
|
|
||||||
uint16_t len = mavlink_msg_to_send_buffer(missionlib_msg_buf, msg);
|
uint16_t len = mavlink_msg_to_send_buffer(buf, msg);
|
||||||
|
mavlink_send_uart_bytes(_channel, buf, len);
|
||||||
mavlink_send_uart_bytes(_channel, missionlib_msg_buf, len);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
@ -1599,6 +1564,7 @@ Mavlink::configure_stream(const char *stream_name, const float rate)
|
||||||
if (interval > 0) {
|
if (interval > 0) {
|
||||||
/* search for stream with specified name in supported streams list */
|
/* search for stream with specified name in supported streams list */
|
||||||
for (unsigned int i = 0; streams_list[i] != nullptr; i++) {
|
for (unsigned int i = 0; streams_list[i] != nullptr; i++) {
|
||||||
|
|
||||||
if (strcmp(stream_name, streams_list[i]->get_name()) == 0) {
|
if (strcmp(stream_name, streams_list[i]->get_name()) == 0) {
|
||||||
/* create new instance */
|
/* create new instance */
|
||||||
stream = streams_list[i]->new_instance();
|
stream = streams_list[i]->new_instance();
|
||||||
|
@ -1904,7 +1870,7 @@ Mavlink::task_main(int argc, char *argv[])
|
||||||
/* if we are passing on mavlink messages, we need to prepare a buffer for this instance */
|
/* if we are passing on mavlink messages, we need to prepare a buffer for this instance */
|
||||||
if (_passing_on) {
|
if (_passing_on) {
|
||||||
/* initialize message buffer if multiplexing is on */
|
/* initialize message buffer if multiplexing is on */
|
||||||
if (OK != message_buffer_init(500)) {
|
if (OK != message_buffer_init(300)) {
|
||||||
errx(1, "can't allocate message buffer, exiting");
|
errx(1, "can't allocate message buffer, exiting");
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1934,9 +1900,12 @@ Mavlink::task_main(int argc, char *argv[])
|
||||||
_task_running = true;
|
_task_running = true;
|
||||||
|
|
||||||
MavlinkOrbSubscription *param_sub = add_orb_subscription(ORB_ID(parameter_update));
|
MavlinkOrbSubscription *param_sub = add_orb_subscription(ORB_ID(parameter_update));
|
||||||
|
uint64_t param_time = 0;
|
||||||
MavlinkOrbSubscription *status_sub = add_orb_subscription(ORB_ID(vehicle_status));
|
MavlinkOrbSubscription *status_sub = add_orb_subscription(ORB_ID(vehicle_status));
|
||||||
|
uint64_t status_time = 0;
|
||||||
|
|
||||||
struct vehicle_status_s *status = (struct vehicle_status_s *) status_sub->get_data();
|
struct vehicle_status_s status;
|
||||||
|
status_sub->update(&status_time, &status);
|
||||||
|
|
||||||
MavlinkCommandsStream commands_stream(this, _channel);
|
MavlinkCommandsStream commands_stream(this, _channel);
|
||||||
|
|
||||||
|
@ -1993,14 +1962,14 @@ Mavlink::task_main(int argc, char *argv[])
|
||||||
|
|
||||||
hrt_abstime t = hrt_absolute_time();
|
hrt_abstime t = hrt_absolute_time();
|
||||||
|
|
||||||
if (param_sub->update(t)) {
|
if (param_sub->update(¶m_time, nullptr)) {
|
||||||
/* parameters updated */
|
/* parameters updated */
|
||||||
mavlink_update_system();
|
mavlink_update_system();
|
||||||
}
|
}
|
||||||
|
|
||||||
if (status_sub->update(t)) {
|
if (status_sub->update(&status_time, &status)) {
|
||||||
/* switch HIL mode if required */
|
/* switch HIL mode if required */
|
||||||
set_hil_enabled(status->hil_state == HIL_STATE_ON);
|
set_hil_enabled(status.hil_state == HIL_STATE_ON);
|
||||||
}
|
}
|
||||||
|
|
||||||
/* update commands stream */
|
/* update commands stream */
|
||||||
|
|
|
@ -277,11 +277,16 @@ private:
|
||||||
int size;
|
int size;
|
||||||
char *data;
|
char *data;
|
||||||
};
|
};
|
||||||
mavlink_message_buffer _message_buffer;
|
mavlink_message_buffer _message_buffer;
|
||||||
|
|
||||||
pthread_mutex_t _message_buffer_mutex;
|
pthread_mutex_t _message_buffer_mutex;
|
||||||
|
|
||||||
perf_counter_t _loop_perf; /**< loop performance counter */
|
perf_counter_t _loop_perf; /**< loop performance counter */
|
||||||
|
bool _param_initialized;
|
||||||
|
param_t _param_system_id;
|
||||||
|
param_t _param_component_id;
|
||||||
|
param_t _param_system_type;
|
||||||
|
param_t _param_use_hil_gps;
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Send one parameter.
|
* Send one parameter.
|
||||||
|
|
File diff suppressed because it is too large
Load Diff
|
@ -43,6 +43,19 @@
|
||||||
|
|
||||||
#include "mavlink_stream.h"
|
#include "mavlink_stream.h"
|
||||||
|
|
||||||
extern MavlinkStream *streams_list[];
|
class StreamListItem {
|
||||||
|
|
||||||
|
public:
|
||||||
|
MavlinkStream* (*new_instance)();
|
||||||
|
const char* (*get_name)();
|
||||||
|
|
||||||
|
StreamListItem(MavlinkStream* (*inst)(), const char* (*name)()) :
|
||||||
|
new_instance(inst),
|
||||||
|
get_name(name) {};
|
||||||
|
|
||||||
|
~StreamListItem() {};
|
||||||
|
};
|
||||||
|
|
||||||
|
extern StreamListItem *streams_list[];
|
||||||
|
|
||||||
#endif /* MAVLINK_MESSAGES_H_ */
|
#endif /* MAVLINK_MESSAGES_H_ */
|
||||||
|
|
|
@ -50,50 +50,55 @@ MavlinkOrbSubscription::MavlinkOrbSubscription(const orb_id_t topic) :
|
||||||
_fd(orb_subscribe(_topic)),
|
_fd(orb_subscribe(_topic)),
|
||||||
_published(false),
|
_published(false),
|
||||||
_topic(topic),
|
_topic(topic),
|
||||||
_last_check(0),
|
|
||||||
next(nullptr)
|
next(nullptr)
|
||||||
{
|
{
|
||||||
_data = malloc(topic->o_size);
|
|
||||||
memset(_data, 0, topic->o_size);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
MavlinkOrbSubscription::~MavlinkOrbSubscription()
|
MavlinkOrbSubscription::~MavlinkOrbSubscription()
|
||||||
{
|
{
|
||||||
close(_fd);
|
close(_fd);
|
||||||
free(_data);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
orb_id_t
|
orb_id_t
|
||||||
MavlinkOrbSubscription::get_topic()
|
MavlinkOrbSubscription::get_topic() const
|
||||||
{
|
{
|
||||||
return _topic;
|
return _topic;
|
||||||
}
|
}
|
||||||
|
|
||||||
void *
|
bool
|
||||||
MavlinkOrbSubscription::get_data()
|
MavlinkOrbSubscription::update(uint64_t *time, void* data)
|
||||||
{
|
{
|
||||||
return _data;
|
// TODO this is NOT atomic operation, we can get data newer than time
|
||||||
|
// if topic was published between orb_stat and orb_copy calls.
|
||||||
|
|
||||||
|
uint64_t time_topic;
|
||||||
|
if (orb_stat(_fd, &time_topic)) {
|
||||||
|
/* error getting last topic publication time */
|
||||||
|
time_topic = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (orb_copy(_topic, _fd, data)) {
|
||||||
|
/* error copying topic data */
|
||||||
|
memset(data, 0, _topic->o_size);
|
||||||
|
return false;
|
||||||
|
|
||||||
|
} else {
|
||||||
|
/* data copied successfully */
|
||||||
|
_published = true;
|
||||||
|
if (time_topic != *time) {
|
||||||
|
*time = time_topic;
|
||||||
|
return true;
|
||||||
|
|
||||||
|
} else {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
bool
|
bool
|
||||||
MavlinkOrbSubscription::update(const hrt_abstime t)
|
MavlinkOrbSubscription::update(void* data)
|
||||||
{
|
{
|
||||||
if (_last_check == t) {
|
return !orb_copy(_topic, _fd, data);
|
||||||
/* already checked right now, return result of the check */
|
|
||||||
return _updated;
|
|
||||||
|
|
||||||
} else {
|
|
||||||
_last_check = t;
|
|
||||||
orb_check(_fd, &_updated);
|
|
||||||
|
|
||||||
if (_updated) {
|
|
||||||
orb_copy(_topic, _fd, _data);
|
|
||||||
_published = true;
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
return false;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
bool
|
bool
|
||||||
|
|
|
@ -48,12 +48,26 @@
|
||||||
class MavlinkOrbSubscription
|
class MavlinkOrbSubscription
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
MavlinkOrbSubscription *next; /*< pointer to next subscription in list */
|
MavlinkOrbSubscription *next; ///< pointer to next subscription in list
|
||||||
|
|
||||||
MavlinkOrbSubscription(const orb_id_t topic);
|
MavlinkOrbSubscription(const orb_id_t topic);
|
||||||
~MavlinkOrbSubscription();
|
~MavlinkOrbSubscription();
|
||||||
|
|
||||||
bool update(const hrt_abstime t);
|
/**
|
||||||
|
* Check if subscription updated and get data.
|
||||||
|
*
|
||||||
|
* @return true only if topic was updated and data copied to buffer successfully.
|
||||||
|
* If topic was not updated since last check it will return false but still copy the data.
|
||||||
|
* If no data available data buffer will be filled with zeroes.
|
||||||
|
*/
|
||||||
|
bool update(uint64_t *time, void* data);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Copy topic data to given buffer.
|
||||||
|
*
|
||||||
|
* @return true only if topic data copied successfully.
|
||||||
|
*/
|
||||||
|
bool update(void* data);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Check if the topic has been published.
|
* Check if the topic has been published.
|
||||||
|
@ -62,16 +76,12 @@ public:
|
||||||
* @return true if the topic has been published at least once.
|
* @return true if the topic has been published at least once.
|
||||||
*/
|
*/
|
||||||
bool is_published();
|
bool is_published();
|
||||||
void *get_data();
|
orb_id_t get_topic() const;
|
||||||
orb_id_t get_topic();
|
|
||||||
|
|
||||||
private:
|
private:
|
||||||
const orb_id_t _topic; /*< topic metadata */
|
const orb_id_t _topic; ///< topic metadata
|
||||||
int _fd; /*< subscription handle */
|
int _fd; ///< subscription handle
|
||||||
bool _published; /*< topic was ever published */
|
bool _published; ///< topic was ever published
|
||||||
void *_data; /*< pointer to data buffer */
|
|
||||||
hrt_abstime _last_check; /*< time of last check */
|
|
||||||
bool _updated; /*< updated on last check */
|
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -952,7 +952,6 @@ MavlinkReceiver::receive_start(Mavlink *parent)
|
||||||
(void)pthread_attr_setschedparam(&receiveloop_attr, ¶m);
|
(void)pthread_attr_setschedparam(&receiveloop_attr, ¶m);
|
||||||
|
|
||||||
pthread_attr_setstacksize(&receiveloop_attr, 2900);
|
pthread_attr_setstacksize(&receiveloop_attr, 2900);
|
||||||
|
|
||||||
pthread_t thread;
|
pthread_t thread;
|
||||||
pthread_create(&thread, &receiveloop_attr, MavlinkReceiver::start_helper, (void *)parent);
|
pthread_create(&thread, &receiveloop_attr, MavlinkReceiver::start_helper, (void *)parent);
|
||||||
|
|
||||||
|
|
|
@ -50,14 +50,6 @@ class MavlinkStream;
|
||||||
|
|
||||||
class MavlinkStream
|
class MavlinkStream
|
||||||
{
|
{
|
||||||
private:
|
|
||||||
hrt_abstime _last_sent;
|
|
||||||
|
|
||||||
protected:
|
|
||||||
mavlink_channel_t _channel;
|
|
||||||
unsigned int _interval;
|
|
||||||
|
|
||||||
virtual void send(const hrt_abstime t) = 0;
|
|
||||||
|
|
||||||
public:
|
public:
|
||||||
MavlinkStream *next;
|
MavlinkStream *next;
|
||||||
|
@ -71,9 +63,19 @@ public:
|
||||||
* @return 0 if updated / sent, -1 if unchanged
|
* @return 0 if updated / sent, -1 if unchanged
|
||||||
*/
|
*/
|
||||||
int update(const hrt_abstime t);
|
int update(const hrt_abstime t);
|
||||||
virtual MavlinkStream *new_instance() = 0;
|
static MavlinkStream *new_instance();
|
||||||
|
static const char *get_name_static();
|
||||||
virtual void subscribe(Mavlink *mavlink) = 0;
|
virtual void subscribe(Mavlink *mavlink) = 0;
|
||||||
virtual const char *get_name() = 0;
|
virtual const char *get_name() const = 0;
|
||||||
|
|
||||||
|
protected:
|
||||||
|
mavlink_channel_t _channel;
|
||||||
|
unsigned int _interval;
|
||||||
|
|
||||||
|
virtual void send(const hrt_abstime t) = 0;
|
||||||
|
|
||||||
|
private:
|
||||||
|
hrt_abstime _last_sent;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue