2013-12-15 03:57:15 -04:00
|
|
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
|
|
|
|
|
|
/*
|
|
|
|
Common GCS MAVLink functions for all vehicle types
|
|
|
|
|
|
|
|
This program is free software: you can redistribute it and/or modify
|
|
|
|
it under the terms of the GNU General Public License as published by
|
|
|
|
the Free Software Foundation, either version 3 of the License, or
|
|
|
|
(at your option) any later version.
|
|
|
|
|
|
|
|
This program is distributed in the hope that it will be useful,
|
|
|
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
|
|
GNU General Public License for more details.
|
|
|
|
|
|
|
|
You should have received a copy of the GNU General Public License
|
|
|
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
|
|
|
|
|
|
|
#include <GCS.h>
|
2014-01-03 20:30:32 -04:00
|
|
|
#include <AP_AHRS.h>
|
2013-12-15 03:57:15 -04:00
|
|
|
|
2013-12-16 20:56:49 -04:00
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
2013-12-15 03:57:15 -04:00
|
|
|
GCS_MAVLINK::GCS_MAVLINK() :
|
|
|
|
waypoint_receive_timeout(1000)
|
|
|
|
{
|
|
|
|
AP_Param::setup_object_defaults(this, var_info);
|
|
|
|
}
|
2013-12-16 20:56:49 -04:00
|
|
|
|
|
|
|
void
|
|
|
|
GCS_MAVLINK::init(AP_HAL::UARTDriver *port)
|
|
|
|
{
|
|
|
|
GCS_Class::init(port);
|
|
|
|
if (port == (AP_HAL::BetterStream*)hal.uartA) {
|
|
|
|
mavlink_comm_0_port = port;
|
|
|
|
chan = MAVLINK_COMM_0;
|
|
|
|
initialised = true;
|
|
|
|
} else if (port == (AP_HAL::BetterStream*)hal.uartC) {
|
|
|
|
mavlink_comm_1_port = port;
|
|
|
|
chan = MAVLINK_COMM_1;
|
|
|
|
initialised = true;
|
|
|
|
#if MAVLINK_COMM_NUM_BUFFERS > 2
|
|
|
|
} else if (port == (AP_HAL::BetterStream*)hal.uartD) {
|
|
|
|
mavlink_comm_2_port = port;
|
|
|
|
chan = MAVLINK_COMM_2;
|
|
|
|
initialised = true;
|
|
|
|
#endif
|
|
|
|
}
|
|
|
|
_queued_parameter = NULL;
|
|
|
|
reset_cli_timeout();
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
uint16_t
|
|
|
|
GCS_MAVLINK::_count_parameters()
|
|
|
|
{
|
|
|
|
// if we haven't cached the parameter count yet...
|
|
|
|
if (0 == _parameter_count) {
|
|
|
|
AP_Param *vp;
|
|
|
|
AP_Param::ParamToken token;
|
|
|
|
|
|
|
|
vp = AP_Param::first(&token, NULL);
|
|
|
|
do {
|
|
|
|
_parameter_count++;
|
|
|
|
} while (NULL != (vp = AP_Param::next_scalar(&token, NULL)));
|
|
|
|
}
|
|
|
|
return _parameter_count;
|
|
|
|
}
|
|
|
|
|
|
|
|
/**
|
|
|
|
* @brief Send the next pending parameter, called from deferred message
|
|
|
|
* handling code
|
|
|
|
*/
|
|
|
|
void
|
|
|
|
GCS_MAVLINK::queued_param_send()
|
|
|
|
{
|
|
|
|
if (!initialised || _queued_parameter == NULL) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
uint16_t bytes_allowed;
|
|
|
|
uint8_t count;
|
|
|
|
uint32_t tnow = hal.scheduler->millis();
|
|
|
|
|
|
|
|
// use at most 30% of bandwidth on parameters. The constant 26 is
|
|
|
|
// 1/(1000 * 1/8 * 0.001 * 0.3)
|
|
|
|
bytes_allowed = 57 * (tnow - _queued_parameter_send_time_ms) * 26;
|
|
|
|
if (bytes_allowed > comm_get_txspace(chan)) {
|
|
|
|
bytes_allowed = comm_get_txspace(chan);
|
|
|
|
}
|
|
|
|
count = bytes_allowed / (MAVLINK_MSG_ID_PARAM_VALUE_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES);
|
|
|
|
|
|
|
|
while (_queued_parameter != NULL && count--) {
|
|
|
|
AP_Param *vp;
|
|
|
|
float value;
|
|
|
|
|
|
|
|
// copy the current parameter and prepare to move to the next
|
|
|
|
vp = _queued_parameter;
|
|
|
|
|
|
|
|
// if the parameter can be cast to float, report it here and break out of the loop
|
|
|
|
value = vp->cast_to_float(_queued_parameter_type);
|
|
|
|
|
|
|
|
char param_name[AP_MAX_NAME_SIZE];
|
|
|
|
vp->copy_name_token(_queued_parameter_token, param_name, sizeof(param_name), true);
|
|
|
|
|
|
|
|
mavlink_msg_param_value_send(
|
|
|
|
chan,
|
|
|
|
param_name,
|
|
|
|
value,
|
|
|
|
mav_var_type(_queued_parameter_type),
|
|
|
|
_queued_parameter_count,
|
|
|
|
_queued_parameter_index);
|
|
|
|
|
|
|
|
_queued_parameter = AP_Param::next_scalar(&_queued_parameter_token, &_queued_parameter_type);
|
|
|
|
_queued_parameter_index++;
|
|
|
|
}
|
|
|
|
_queued_parameter_send_time_ms = tnow;
|
|
|
|
}
|
|
|
|
|
|
|
|
/**
|
|
|
|
* @brief Send the next pending waypoint, called from deferred message
|
|
|
|
* handling code
|
|
|
|
*/
|
|
|
|
void
|
|
|
|
GCS_MAVLINK::queued_waypoint_send()
|
|
|
|
{
|
|
|
|
if (initialised &&
|
|
|
|
waypoint_receiving &&
|
|
|
|
waypoint_request_i <= waypoint_request_last) {
|
|
|
|
mavlink_msg_mission_request_send(
|
|
|
|
chan,
|
|
|
|
waypoint_dest_sysid,
|
|
|
|
waypoint_dest_compid,
|
|
|
|
waypoint_request_i);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
void GCS_MAVLINK::reset_cli_timeout() {
|
|
|
|
_cli_timeout = hal.scheduler->millis();
|
|
|
|
}
|
2013-12-28 01:00:19 -04:00
|
|
|
|
|
|
|
void GCS_MAVLINK::send_meminfo(void)
|
|
|
|
{
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
|
|
|
extern unsigned __brkval;
|
|
|
|
#else
|
|
|
|
unsigned __brkval = 0;
|
|
|
|
#endif
|
|
|
|
mavlink_msg_meminfo_send(chan, __brkval, hal.util->available_memory());
|
|
|
|
}
|
|
|
|
|
2014-02-13 07:07:13 -04:00
|
|
|
// report power supply status
|
|
|
|
void GCS_MAVLINK::send_power_status(void)
|
|
|
|
{
|
|
|
|
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V2
|
|
|
|
mavlink_msg_power_status_send(chan,
|
|
|
|
hal.analogin->board_voltage() * 1000,
|
|
|
|
hal.analogin->servorail_voltage() * 1000,
|
|
|
|
hal.analogin->power_status_flags());
|
|
|
|
#endif
|
|
|
|
}
|
2014-01-03 20:30:32 -04:00
|
|
|
|
|
|
|
// report AHRS2 state
|
|
|
|
void GCS_MAVLINK::send_ahrs2(AP_AHRS &ahrs)
|
|
|
|
{
|
|
|
|
#if AP_AHRS_NAVEKF_AVAILABLE
|
|
|
|
Vector3f euler;
|
|
|
|
struct Location loc;
|
|
|
|
if (ahrs.get_secondary_attitude(euler) && ahrs.get_secondary_position(loc)) {
|
|
|
|
mavlink_msg_ahrs2_send(chan,
|
|
|
|
euler.x,
|
|
|
|
euler.y,
|
|
|
|
euler.z,
|
|
|
|
loc.alt*1.0e-2f,
|
|
|
|
loc.lat,
|
|
|
|
loc.lng);
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
}
|