mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-04 15:08:28 -04:00
c462adf2ee
The five methods moved from the vehicle specific code are handle_mission_request_list, set_current, count, clear_all and write_partial_list
368 lines
12 KiB
C++
368 lines
12 KiB
C++
// -*- 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>
|
|
#include <AP_AHRS.h>
|
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
GCS_MAVLINK::GCS_MAVLINK() :
|
|
waypoint_receive_timeout(1000)
|
|
{
|
|
AP_Param::setup_object_defaults(this, var_info);
|
|
}
|
|
|
|
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();
|
|
}
|
|
|
|
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());
|
|
}
|
|
|
|
// 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
|
|
}
|
|
|
|
// 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
|
|
}
|
|
|
|
/*
|
|
handle a MISSION_REQUEST_LIST mavlink packet
|
|
*/
|
|
void GCS_MAVLINK::handle_mission_request_list(AP_Mission &mission, mavlink_message_t *msg)
|
|
{
|
|
// decode
|
|
mavlink_mission_request_list_t packet;
|
|
mavlink_msg_mission_request_list_decode(msg, &packet);
|
|
|
|
// exit immediately if this command is not meant for this vehicle
|
|
if (mavlink_check_target(packet.target_system, packet.target_component)) {
|
|
return;
|
|
}
|
|
|
|
// reply with number of commands in the mission. The GCS will then request each command separately
|
|
mavlink_msg_mission_count_send(chan,msg->sysid, msg->compid, mission.num_commands());
|
|
|
|
// set variables to help handle the expected sending of commands to the GCS
|
|
waypoint_receiving = false; // record that we are sending commands (i.e. not receiving)
|
|
waypoint_dest_sysid = msg->sysid; // record system id of GCS who has requested the commands
|
|
waypoint_dest_compid = msg->compid; // record component id of GCS who has requested the commands
|
|
}
|
|
|
|
/*
|
|
handle a MISSION_REQUEST mavlink packet
|
|
*/
|
|
void GCS_MAVLINK::handle_mission_request(AP_Mission &mission, mavlink_message_t *msg,
|
|
AP_Mission::Mission_Command &cmd)
|
|
{
|
|
// decode
|
|
mavlink_mission_request_t packet;
|
|
mavlink_msg_mission_request_decode(msg, &packet);
|
|
|
|
// exit immediately if this command is not meant for this vehicle
|
|
if (mavlink_check_target(packet.target_system, packet.target_component)) {
|
|
return;
|
|
}
|
|
|
|
// retrieve mission from eeprom
|
|
if (!mission.read_cmd_from_storage(packet.seq, cmd)) {
|
|
goto mission_item_send_failed;
|
|
}
|
|
|
|
// convert mission command to mavlink mission item packet
|
|
mavlink_mission_item_t ret_packet;
|
|
memset(&ret_packet, 0, sizeof(ret_packet));
|
|
if (!AP_Mission::mission_cmd_to_mavlink(cmd, ret_packet)) {
|
|
goto mission_item_send_failed;
|
|
}
|
|
|
|
// set packet's current field to 1 if this is the command being executed
|
|
if (cmd.id == (uint16_t)mission.get_current_nav_cmd().index) {
|
|
ret_packet.current = 1;
|
|
} else {
|
|
ret_packet.current = 0;
|
|
}
|
|
|
|
// set auto continue to 1
|
|
ret_packet.autocontinue = 1; // 1 (true), 0 (false)
|
|
|
|
/*
|
|
avoid the _send() function to save memory on APM2, as it avoids
|
|
the stack usage of the _send() function by using the already
|
|
declared ret_packet above
|
|
*/
|
|
ret_packet.target_system = msg->sysid;
|
|
ret_packet.target_component = msg->compid;
|
|
ret_packet.seq = packet.seq;
|
|
ret_packet.command = cmd.id;
|
|
|
|
_mav_finalize_message_chan_send(chan,
|
|
MAVLINK_MSG_ID_MISSION_ITEM,
|
|
(const char *)&ret_packet,
|
|
MAVLINK_MSG_ID_MISSION_ITEM_LEN,
|
|
MAVLINK_MSG_ID_MISSION_ITEM_CRC);
|
|
return;
|
|
|
|
mission_item_send_failed:
|
|
// send failure message
|
|
mavlink_msg_mission_ack_send(chan, msg->sysid, msg->compid, MAV_MISSION_ERROR);
|
|
}
|
|
|
|
/*
|
|
handle a MISSION_SET_CURRENT mavlink packet
|
|
*/
|
|
void GCS_MAVLINK::handle_mission_set_current(AP_Mission &mission, mavlink_message_t *msg)
|
|
{
|
|
// decode
|
|
mavlink_mission_set_current_t packet;
|
|
mavlink_msg_mission_set_current_decode(msg, &packet);
|
|
|
|
// exit immediately if this command is not meant for this vehicle
|
|
if (mavlink_check_target(packet.target_system,packet.target_component)) {
|
|
return;
|
|
}
|
|
|
|
// set current command
|
|
if (mission.set_current_cmd(packet.seq)) {
|
|
mavlink_msg_mission_current_send(chan, mission.get_current_nav_cmd().index);
|
|
}
|
|
}
|
|
|
|
/*
|
|
handle a MISSION_COUNT mavlink packet
|
|
*/
|
|
void GCS_MAVLINK::handle_mission_count(AP_Mission &mission, mavlink_message_t *msg)
|
|
{
|
|
// decode
|
|
mavlink_mission_count_t packet;
|
|
mavlink_msg_mission_count_decode(msg, &packet);
|
|
|
|
// exit immediately if this command is not meant for this vehicle
|
|
if (mavlink_check_target(packet.target_system,packet.target_component)) {
|
|
return;
|
|
}
|
|
|
|
// start waypoint receiving
|
|
if (packet.count > mission.num_commands_max()) {
|
|
// send NAK
|
|
mavlink_msg_mission_ack_send(chan, msg->sysid, msg->compid, MAV_MISSION_NO_SPACE);
|
|
return;
|
|
}
|
|
|
|
// new mission arriving, truncate mission to be the same length
|
|
mission.truncate(packet.count);
|
|
|
|
// set variables to help handle the expected receiving of commands from the GCS
|
|
waypoint_timelast_receive = hal.scheduler->millis(); // set time we last received commands to now
|
|
waypoint_receiving = true; // record that we expect to receive commands
|
|
waypoint_request_i = 0; // reset the next expected command number to zero
|
|
waypoint_request_last = packet.count; // record how many commands we expect to receive
|
|
waypoint_timelast_request = 0; // set time we last requested commands to zero
|
|
}
|
|
|
|
/*
|
|
handle a MISSION_CLEAR_ALL mavlink packet
|
|
*/
|
|
void GCS_MAVLINK::handle_mission_clear_all(AP_Mission &mission, mavlink_message_t *msg)
|
|
{
|
|
// decode
|
|
mavlink_mission_clear_all_t packet;
|
|
mavlink_msg_mission_clear_all_decode(msg, &packet);
|
|
|
|
// exit immediately if this command is not meant for this vehicle
|
|
if (mavlink_check_target(packet.target_system, packet.target_component)) {
|
|
return;
|
|
}
|
|
|
|
// clear all waypoints
|
|
if (mission.clear()) {
|
|
// send ack
|
|
mavlink_msg_mission_ack_send(chan, msg->sysid, msg->compid, MAV_RESULT_ACCEPTED);
|
|
}else{
|
|
// send nack
|
|
mavlink_msg_mission_ack_send(chan, msg->sysid, msg->compid, 1);
|
|
}
|
|
}
|
|
|
|
/*
|
|
handle a MISSION_WRITE_PARTIAL_LIST mavlink packet
|
|
*/
|
|
void GCS_MAVLINK::handle_mission_write_partial_list(AP_Mission &mission, mavlink_message_t *msg)
|
|
{
|
|
// decode
|
|
mavlink_mission_write_partial_list_t packet;
|
|
mavlink_msg_mission_write_partial_list_decode(msg, &packet);
|
|
|
|
// exit immediately if this command is not meant for this vehicle
|
|
if (mavlink_check_target(packet.target_system,packet.target_component)) {
|
|
return;
|
|
}
|
|
|
|
// start waypoint receiving
|
|
if (packet.start_index > mission.num_commands() ||
|
|
packet.end_index > mission.num_commands() ||
|
|
packet.end_index < packet.start_index) {
|
|
send_text_P(SEVERITY_LOW,PSTR("flight plan update rejected"));
|
|
return;
|
|
}
|
|
|
|
waypoint_timelast_receive = hal.scheduler->millis();
|
|
waypoint_timelast_request = 0;
|
|
waypoint_receiving = true;
|
|
waypoint_request_i = packet.start_index;
|
|
waypoint_request_last= packet.end_index;
|
|
}
|